24 #define NUM_SERVO_CHANNELS 16 181 function.set_and_save(int8_t(f));
186 reversed.set_and_save_ifchanged(r?1:0);
193 return function.configured();
226 void calc_pwm(int16_t output_scaled);
270 static void set_output_pwm_chan(uint8_t
chan, uint16_t
value);
293 static void output_ch_all(
void);
305 void save_trim(
void);
309 flags.k_throttle_reversible =
true;
313 static void output_trim_all(
void);
316 static void setup_failsafe_trim_all(
void);
343 static void copy_radio_in_out_mask(uint16_t mask);
362 int16_t value, int16_t angle_min, int16_t angle_max);
365 static void enable_aux_servos(
void);
368 static void enable_by_mask(uint16_t mask);
374 static void update_aux_servo_function(
void);
396 disabled_passthrough = disable;
410 static bool upgrade_parameters(
const uint8_t old_keys[14], uint16_t aux_channel_mask,
RCMapper *rcmap);
411 static void upgrade_motors_servo(uint8_t ap_motors_key, uint8_t ap_motors_idx, uint8_t new_channel);
452 #if HAL_SUPPORT_RCOUT_SERIAL 455 static AP_BLHeli *blheli_ptr;
474 return disabled_passthrough;
differential spoiler 1 (left wing)
static SRV_Channel::Aux_servo_function_t get_motor_function(uint8_t channel)
void set_output_max(uint16_t pwm)
SRV_Channel::servo_mask_t channel_mask
uint16_t get_limit_pwm(LimitValue limit) const
This must be the last enum value (only add new values before this one)
static bool passthrough_disabled(void)
static bool is_motor(SRV_Channel::Aux_servo_function_t function)
SRV_Channel::Aux_servo_function_t get_function(void) const
uint16_t pwm_from_range(int16_t scaled_value) const
crop sprayer pump channel
void set_angle(int16_t angle)
aileron, with rc input, deprecated
void set_range(uint16_t high)
engine kill switch, used for gas airplanes and helicopters
static uint16_t disabled_mask
static AP_SBusOut * sbus_ptr
void reversed_set_and_save_ifchanged(bool r)
float get_output_norm(void)
differential spoiler 1 (right wing)
uint16_t get_output_max(void) const
these are for pass-thru from arbitrary rc inputs
differential spoiler 2 (left wing)
tiltrotor motor tilt control
static bool disabled_passthrough
void output_ch(void)
map a function to a servo channel and output it
void disable_passthrough(bool disable)
static uint16_t channels[SRXL_MAX_CHANNELS]
crop sprayer spinner channel
uint16_t pwm_from_angle(int16_t scaled_value) const
static SRV_Channel * channels
mount open (deploy) / close (retract)
A system for managing and storing variables that are of general interest to the system.
void aux_servo_function_setup(void)
static SRV_Channel * srv_channel(uint8_t i)
bool k_throttle_reversible
these allow remapping of copter motors
manual, just pass-thru the RC in signal
friend class SRV_Channels
vectored thrust, left tilt
helicopter tail RSC output
SRV_Channel::servo_mask_t trimmed_mask
uint16_t get_output_min(void) const
void set_reversible_throttle(void)
elevator, with rc input, deprecated
bool function_configured(void) const
vectored thrust, right tilt
Common definitions and utility routines for the ArduPilot libraries.
uint16_t get_trim(void) const
static Bitmask function_mask
static void set_disabled_channel_mask(uint16_t mask)
void set_output_min(uint16_t pwm)
uint16_t get_output_pwm(void) const
void function_set_and_save(SRV_Channel::Aux_servo_function_t f)
AP_HAL::AnalogSource * chan
bool get_reversed(void) const
differential spoiler 2 (right wing)
bool auto_trim_enabled(void) const
static servo_mask_t have_pwm_mask
ground steering, used to separate from rudder
static SRV_Channels * instance
static const struct AP_Param::GroupInfo var_info[]
#define NUM_SERVO_CHANNELS
void set_output_pwm(uint16_t pwm)
void calc_pwm(int16_t output_scaled)
static AP_Volz_Protocol * volz_ptr
mount2 open (deploy) / close (retract)
vertical booster throttle