30 int8_t passthrough_from = -1;
39 passthrough_from = int8_t(
function -
k_rcin1);
42 if (passthrough_from != -1) {
136 function_mask.clearall();
139 functions[i].channel_mask = 0;
144 if ((uint8_t)
channels[i].
function.
get() < SRV_Channel::k_nr_aux_servo_functions) {
145 channels[i].aux_servo_function_setup();
146 function_mask.set((uint8_t)
channels[i].
function.
get());
147 functions[
channels[i].function.get()].channel_mask |= 1U<<i;
158 update_aux_servo_function();
170 #if HAL_SUPPORT_RCOUT_SERIAL 171 blheli_ptr->update();
178 for (uint8_t i = 0; i < 16; i++) {
179 if (mask & (1U<<i)) {
190 if (!function_assigned(
function)) {
194 if (
channels[i].
function.
get() ==
function) {
208 if (!function_assigned(
function)) {
212 if (
channels[i].
function.
get() ==
function) {
213 int16_t value2 = value - 1500 +
channels[i].get_trim();
227 if (!function_assigned(
function)) {
231 if (
channels[i].
function.
get() ==
function) {
243 if (!function_assigned(
function)) {
247 if (
channels[i].
function.
get() ==
function) {
252 if (do_input_output) {
256 if (do_input_output) {
270 if ((1U<<i) & mask) {
287 if (!function_assigned(
function)) {
292 if (ch.
function.get() ==
function) {
304 if (!function_assigned(
function)) {
309 if (ch.
function.get() ==
function) {
322 if (!function_assigned(
function)) {
327 if (ch.
function.get() ==
function) {
340 if (!function_assigned(
function)) {
345 if (ch.
function.get() ==
function) {
366 return function_mask.get(uint16_t(
function));
375 int16_t
value, int16_t angle_min, int16_t angle_max)
377 if (!function_assigned(
function)) {
380 if (angle_max <= angle_min) {
383 float v = float(value - angle_min) / float(angle_max - angle_min);
387 if (ch.
function.get() ==
function) {
401 update_aux_servo_function();
403 if (function_assigned(
function)) {
408 if (
channels[channel].
function ==
function) {
413 (
unsigned)
channels[channel].
function);
416 channels[channel].type_setup =
false;
417 channels[channel].function.set(
function);
418 channels[channel].aux_servo_function_setup();
419 function_mask.set((uint8_t)
function);
420 functions[
function].channel_mask |= 1U<<channel;
428 update_aux_servo_function();
430 if (!function_assigned(
function)) {
434 if (
channels[i].
function ==
function) {
448 if (default_chan >= 0) {
449 set_aux_channel_default(
function, default_chan);
451 if (!find_channel(
function, chan)) {
460 functions[
function].output_scaled =
value;
468 return functions[
function].output_scaled;
479 update_aux_servo_function();
482 return functions[
function].channel_mask;
492 if (
channels[i].
function ==
function) {
502 if (
channels[i].
function ==
function) {
516 if (old !=
channels[chan].
function &&
channels[chan].
function ==
function) {
517 function_mask.set((uint8_t)
function);
525 if (find_channel(
function, chan)) {
547 if (change > 0 && trim_scaled < 0.6
f) {
549 }
else if (change < 0 && trim_scaled > 0.4
f) {
556 trimmed_mask |= 1U<<i;
564 if (!find_channel(
function, chan)) {
567 channels[
chan].calc_pwm(functions[
function].output_scaled);
576 if (
channels[i].
function ==
function) {
586 if (
channels[i].
function ==
function) {
600 if (!find_channel(
function, chan)) {
603 channels[
chan].calc_pwm(functions[
function].output_scaled);
613 if (slew_rate <= 0) {
620 ch.
calc_pwm(functions[
function].output_scaled);
626 if (max_change == 0 || dt > 1) {
641 if (
channels[i].
function ==
function) {
651 if (
channels[i].
function ==
function) {
689 if (
channels[15].
function.configured_in_storage()) {
695 for (uint8_t i=0; i<14; i++) {
696 uint8_t k = rc_keys[i];
708 const struct mapping {
721 bool is_aux = aux_channel_mask & (1U<<i);
723 for (uint8_t j=0; j<
ARRAY_SIZE(mapping); j++) {
724 const struct mapping &m = mapping[j];
729 bool aux_only = (m.flags & FLAG_AUX_ONLY)!=0;
730 if (!is_aux && aux_only) {
745 if (m.flags & FLAG_IS_REVERSE) {
747 v8.set(v8.get() == -1?1:0);
750 if (!m.new_srv_param->configured_in_storage()) {
753 ((AP_Int16 *)m.new_srv_param)->set_and_save_ifchanged(v16.get());
755 ((AP_Int8 *)m.new_srv_param)->set_and_save_ifchanged(v8.get());
758 if (m.new_rc_param && !m.new_rc_param->configured_in_storage()) {
761 ((AP_Int16 *)m.new_rc_param)->set_and_save_ifchanged(v16.get());
763 ((AP_Int8 *)m.new_rc_param)->set_and_save_ifchanged(v8.get());
769 if (rcmap !=
nullptr) {
771 const int8_t func_map[4] = {
channels[0].function.get(),
776 for (uint8_t i=0; i<4; i++) {
777 uint8_t m = uint8_t(map[i]-1);
778 if (m != i && m < 4) {
779 channels[m].function.set_and_save_ifchanged(func_map[i]);
802 const struct mapping {
814 for (uint8_t j=0; j<
ARRAY_SIZE(mapping); j++) {
815 const struct mapping &m = mapping[j];
831 if (m.flags & FLAG_IS_REVERSE) {
833 v8.set(v8.get() == -1?1:0);
840 ((AP_Int16 *)m.new_srv_param)->set_and_save_ifchanged(v16.get());
842 ((AP_Int8 *)m.new_srv_param)->set_and_save_ifchanged(v8.get());
differential spoiler 1 (left wing)
static void set_angle(SRV_Channel::Aux_servo_function_t function, uint16_t angle)
static void copy_radio_in_out(SRV_Channel::Aux_servo_function_t function, bool do_input_output=false)
static void upgrade_motors_servo(uint8_t ap_motors_key, uint8_t ap_motors_idx, uint8_t new_channel)
static void move_servo(SRV_Channel::Aux_servo_function_t function, int16_t value, int16_t angle_min, int16_t angle_max)
uint16_t get_limit_pwm(LimitValue limit) const
This must be the last enum value (only add new values before this one)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
static bool passthrough_disabled(void)
static void set_trim_to_min_for(SRV_Channel::Aux_servo_function_t function)
int16_t get_radio_trim() const
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
static int16_t get_output_scaled(SRV_Channel::Aux_servo_function_t function)
static void set_output_pwm_first(SRV_Channel::Aux_servo_function_t function, uint16_t value)
void set_angle(int16_t angle)
aileron, with rc input, deprecated
static bool find_old_parameter(const struct ConversionInfo *info, AP_Param *value)
void set_range(uint16_t high)
static uint16_t disabled_mask
static bool upgrade_parameters(const uint8_t old_keys[14], uint16_t aux_channel_mask, RCMapper *rcmap)
AP_HAL::UARTDriver * console
static void set_trim_to_servo_out_for(SRV_Channel::Aux_servo_function_t function)
virtual void set_esc_scaling(uint16_t min_pwm, uint16_t max_pwm)
int16_t get_radio_in() const
static RC_Channel * rc_channel(uint8_t chan)
static bool set_aux_channel_default(SRV_Channel::Aux_servo_function_t function, uint8_t channel)
static void limit_slew_rate(SRV_Channel::Aux_servo_function_t function, float slew_rate, float dt)
virtual void set_freq(uint32_t chmask, uint16_t freq_hz)=0
differential spoiler 1 (right wing)
static void set_output_to_trim(SRV_Channel::Aux_servo_function_t function)
uint16_t get_output_max(void) const
static void set_range(SRV_Channel::Aux_servo_function_t function, uint16_t range)
void set_radio_in(int16_t val)
these are for pass-thru from arbitrary rc inputs
differential spoiler 2 (left wing)
static SRV_Channel * get_channel_for(SRV_Channel::Aux_servo_function_t function, int8_t default_chan=-1)
virtual uint16_t read_last_sent(uint8_t ch)
tiltrotor motor tilt control
static bool get_output_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t &value)
void output_ch(void)
map a function to a servo channel and output it
static void constrain_pwm(SRV_Channel::Aux_servo_function_t function)
uint8_t roll() const
roll - return input channel number for roll / aileron input
static void update_aux_servo_function(void)
setup the output range types of all functions
static uint16_t channels[SRXL_MAX_CHANNELS]
static void set_output_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit)
static bool find_channel(SRV_Channel::Aux_servo_function_t function, uint8_t &chan)
uint8_t yaw() const
yaw - return input channel number for yaw / rudder input
virtual void set_safety_pwm(uint32_t chmask, uint16_t period_us)
uint8_t pitch() const
pitch - return input channel number for pitch / elevator input
static void output_ch_all(void)
virtual void enable_ch(uint8_t ch)=0
void aux_servo_function_setup(void)
virtual void printf(const char *,...) FMT_PRINTF(2
virtual void set_default_rate(uint16_t rate_hz)
static void set_output_scaled(SRV_Channel::Aux_servo_function_t function, int16_t value)
RC_Channel manager, with EEPROM-backed storage of constants.
Object managing one RC channel.
bool is_zero(const T fVal1)
static void set_output_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t value)
manual, just pass-thru the RC in signal
virtual void set_failsafe_pwm(uint32_t chmask, uint16_t period_us)
vectored thrust, left tilt
helicopter tail RSC output
uint16_t get_output_min(void) const
virtual void write(uint8_t ch, uint16_t period_us)=0
elevator, with rc input, deprecated
static void enable_aux_servos(void)
Should be called after the the servo functions have been initialized.
static void set_safety_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit)
static void copy_radio_in_out_mask(uint16_t mask)
vectored thrust, right tilt
static void set_failsafe_limit(SRV_Channel::Aux_servo_function_t function, SRV_Channel::LimitValue limit)
void adjust_trim(SRV_Channel::Aux_servo_function_t function, float v)
float constrain_float(const float amt, const float low, const float high)
static void set_rc_frequency(SRV_Channel::Aux_servo_function_t function, uint16_t frequency)
static RC_Channel * channels
uint32_t old_group_element
static uint16_t get_output_channel_mask(SRV_Channel::Aux_servo_function_t function)
AP_HAL::AnalogSource * chan
void set_esc_scaling_for(SRV_Channel::Aux_servo_function_t function)
static float get_output_norm(SRV_Channel::Aux_servo_function_t function)
bool get_reversed(void) const
differential spoiler 2 (right wing)
uint8_t throttle() const
throttle - return input channel number for throttle input
static servo_mask_t have_pwm_mask
static void set_default_function(uint8_t chan, SRV_Channel::Aux_servo_function_t function)
ground steering, used to separate from rudder
static SRV_Channel::Aux_servo_function_t channel_function(uint8_t channel)
#define NUM_SERVO_CHANNELS
void set_output_pwm(uint16_t pwm)
static void enable_by_mask(uint16_t mask)
enable output channels using a channel mask
void calc_pwm(int16_t output_scaled)
static bool function_assigned(SRV_Channel::Aux_servo_function_t function)
static void set_output_pwm_trimmed(SRV_Channel::Aux_servo_function_t function, int16_t value)
static void set_trim_to_pwm_for(SRV_Channel::Aux_servo_function_t function, int16_t pwm)
static void set_failsafe_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t pwm)
vertical booster throttle