11 void drive(uint16_t hz_speed);
13 #define MENU_FUNC(func) FUNCTOR_BIND(&commands, &Menu_Commands::func, int8_t, uint8_t, const Menu::arg *) 35 static uint16_t
pwm = 1500;
43 for (uint8_t i = 0; i < 14; i++) {
49 }
else if (
delta < 0 &&
pwm <= 1000) {
76 MENU(menu,
"Menu: ", rcoutput_menu_commands);
81 for (uint8_t i = 0; i < 14; i++) {
const struct Menu::command rcoutput_menu_commands[]
AP_HAL::UARTDriver * console
virtual void set_freq(uint32_t chmask, uint16_t freq_hz)=0
void drive(uint16_t hz_speed)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
virtual void delay(uint16_t ms)=0
virtual void enable_ch(uint8_t ch)=0
virtual void printf(const char *,...) FMT_PRINTF(2
MENU(menu, "Menu: ", rcoutput_menu_commands)
int8_t menu_esc(uint8_t argc, const Menu::arg *argv)
virtual void write(uint8_t ch, uint16_t period_us)=0
Common definitions and utility routines for the ArduPilot libraries.
virtual uint32_t available()=0
int8_t menu_servo(uint8_t argc, const Menu::arg *argv)
AP_HAL::Scheduler * scheduler