mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
SRV_Channel: added copy_radio_in_out_mask()
This commit is contained in:
parent
fedd2c558c
commit
99f5229a34
@ -328,9 +328,12 @@ public:
|
||||
// set output to trim value
|
||||
static void set_output_to_trim(SRV_Channel::Aux_servo_function_t function);
|
||||
|
||||
// copy radio_in to radio_out
|
||||
// copy radio_in to servo out
|
||||
static void copy_radio_in_out(SRV_Channel::Aux_servo_function_t function, bool do_input_output=false);
|
||||
|
||||
// copy radio_in to servo_out by channel mask
|
||||
static void copy_radio_in_out_mask(uint16_t mask);
|
||||
|
||||
// setup failsafe for an auxiliary channel function, by pwm
|
||||
static void set_failsafe_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t pwm);
|
||||
|
||||
|
@ -255,6 +255,24 @@ SRV_Channels::copy_radio_in_out(SRV_Channel::Aux_servo_function_t function, bool
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
copy radio_in to radio_out for a channel mask
|
||||
*/
|
||||
void
|
||||
SRV_Channels::copy_radio_in_out_mask(uint16_t mask)
|
||||
{
|
||||
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
|
||||
if ((1U<<i) & mask) {
|
||||
RC_Channel *rc = RC_Channels::rc_channel(channels[i].ch_num);
|
||||
if (rc == nullptr) {
|
||||
continue;
|
||||
}
|
||||
channels[i].set_output_pwm(rc->get_radio_in());
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/*
|
||||
setup failsafe value for an auxiliary function type to a LimitValue
|
||||
*/
|
||||
|
Loading…
Reference in New Issue
Block a user