RC_Channel: added disable_passthrough() method

This commit is contained in:
Andrew Tridgell 2016-09-18 09:38:34 +10:00
parent 57ddc8f58f
commit 78ef3b77c6
2 changed files with 17 additions and 2 deletions

View File

@ -22,6 +22,7 @@ const AP_Param::GroupInfo RC_Channel_aux::var_info[] = {
RC_Channel_aux *RC_Channel_aux::_aux_channels[RC_AUX_MAX_CHANNELS];
uint64_t RC_Channel_aux::_function_mask[2];
bool RC_Channel_aux::_initialised;
bool RC_Channel_aux::_disable_passthrough;
void
RC_Channel_aux::set_function_mask(uint8_t fn)
@ -47,10 +48,18 @@ RC_Channel_aux::output_ch(void)
case k_none: // disabled
return;
case k_manual: // manual
set_radio_out(get_radio_in());
if (_disable_passthrough) {
set_radio_out(get_radio_trim());
} else {
set_radio_out(get_radio_in());
}
break;
case k_rcin1 ... k_rcin16: // rc pass-thru
set_radio_out(hal.rcin->read(function-k_rcin1));
if (_disable_passthrough) {
set_radio_out(get_radio_trim());
} else {
set_radio_out(hal.rcin->read(function-k_rcin1));
}
break;
case k_motor1 ... k_motor8:
// handled by AP_Motors::rc_write()

View File

@ -165,11 +165,17 @@ public:
// find first channel that a function is assigned to
static bool find_channel(Aux_servo_function_t function, uint8_t &chan);
// control pass-thru of channels
static void disable_passthrough(bool disable) {
_disable_passthrough = disable;
}
private:
static uint64_t _function_mask[2];
static bool _initialised;
static RC_Channel_aux *_aux_channels[RC_AUX_MAX_CHANNELS];
static bool _disable_passthrough;
void aux_servo_function_setup(void);
static void set_function_mask(uint8_t function);