8 #define RC_CHANNEL_TYPE_ANGLE 0 9 #define RC_CHANNEL_TYPE_RANGE 1 11 #define NUM_RC_CHANNELS 16 69 uint16_t
read()
const;
150 static uint8_t
get_radio_in(uint16_t *chans,
const uint8_t num_channels);
153 static uint8_t get_valid_channel_count(
void);
154 static int16_t get_receiver_rssi(
void);
155 static bool read_input(
void);
156 static void clear_overrides(
void);
157 static bool receiver_bind(
const int dsmMode);
158 static bool set_override(
const uint8_t chan,
const int16_t
value);
int16_t pwm_to_angle_dz(uint16_t dead_zone)
void set_range(uint16_t high)
void set_radio_min(int16_t val)
int16_t get_radio_trim() const
int16_t get_control_mid() const
void recompute_pwm_no_deadzone()
int16_t get_radio_in() const
static RC_Channel * rc_channel(uint8_t chan)
void set_pwm(int16_t pwm)
void set_radio_max(int16_t val)
void set_radio_in(int16_t val)
void set_angle(uint16_t angle)
void set_radio_trim(int16_t val)
static uint16_t channels[SRXL_MAX_CHANNELS]
void set_control_in(int16_t val)
uint16_t get_dead_zone(void) const
void set_and_save_radio_trim(int16_t val)
A system for managing and storing variables that are of general interest to the system.
int16_t get_control_in() const
static const struct AP_Param::GroupInfo var_info[]
Object managing one RC channel.
bool min_max_configured() const
Common definitions and utility routines for the ArduPilot libraries.
int16_t get_control_in_zero_dz(void)
static RC_Channel * channels
bool get_reverse(void) const
AP_HAL::AnalogSource * chan
int16_t get_radio_min() const
int16_t get_radio_max() const
int16_t pwm_to_range_dz(uint16_t dead_zone)
int16_t pwm_to_angle_dz_trim(uint16_t dead_zone, uint16_t trim)
static uint32_t configured_mask
void set_default_dead_zone(int16_t dzone)