14 #define NUM_CHANNELS 8 63 hal.
console->
printf(
"ch%u: %4d ", (
unsigned)i+1, (
int)rc[i].get_control_in());
74 (
unsigned)rc[i].get_radio_min(),
75 (
unsigned)rc[i].get_radio_max());
static void print_pwm(void)
void set_range(uint16_t high)
AP_HAL::UARTDriver * console
static RC_Channel * rc_channel(uint8_t chan)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
static RC_Channels rc_channels
void set_angle(uint16_t angle)
virtual void delay(uint16_t ms)=0
virtual void printf(const char *,...) FMT_PRINTF(2
RC_Channel manager, with EEPROM-backed storage of constants.
Object managing one RC channel.
static bool read_input(void)
static void print_radio_values()
void set_default_dead_zone(int16_t dzone)
AP_HAL::Scheduler * scheduler