mirror of https://github.com/ArduPilot/ardupilot
SRV_Channel: don't count disabled channels in mask and setup functions
disable channels that are not in use
This commit is contained in:
parent
4fa0e275fd
commit
6511a65b67
|
@ -183,7 +183,7 @@ public:
|
|||
|
||||
// check if a function is valid for indexing into functions
|
||||
static bool valid_function(Aux_servo_function_t fn) {
|
||||
return fn >= 0 && fn < k_nr_aux_servo_functions;
|
||||
return fn > k_none && fn < k_nr_aux_servo_functions;
|
||||
}
|
||||
bool valid_function(void) const {
|
||||
return valid_function(function);
|
||||
|
|
|
@ -208,6 +208,8 @@ void SRV_Channels::enable_aux_servos()
|
|||
// see if it is a valid function
|
||||
if (c.valid_function()) {
|
||||
hal.rcout->enable_ch(c.ch_num);
|
||||
} else {
|
||||
hal.rcout->disable_ch(c.ch_num);
|
||||
}
|
||||
|
||||
// output some servo functions before we fiddle with the
|
||||
|
|
Loading…
Reference in New Issue