mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
SRV_Channel: update_aux_servo_function first checks function is valid
This resolves a bug in which the board could become unresponsive if an invalid function is selected
This commit is contained in:
parent
60834e9af0
commit
9123b6034e
@ -140,9 +140,11 @@ void SRV_Channels::update_aux_servo_function(void)
|
|||||||
|
|
||||||
// set auxiliary ranges
|
// set auxiliary ranges
|
||||||
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
|
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
|
||||||
channels[i].aux_servo_function_setup();
|
if ((uint8_t)channels[i].function.get() < SRV_Channel::k_nr_aux_servo_functions) {
|
||||||
function_mask.set((uint8_t)channels[i].function.get());
|
channels[i].aux_servo_function_setup();
|
||||||
functions[channels[i].function.get()].channel_mask |= 1U<<i;
|
function_mask.set((uint8_t)channels[i].function.get());
|
||||||
|
functions[channels[i].function.get()].channel_mask |= 1U<<i;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
initialised = true;
|
initialised = true;
|
||||||
}
|
}
|
||||||
@ -158,9 +160,8 @@ void SRV_Channels::enable_aux_servos()
|
|||||||
// includes k_none servos, which allows those to get their initial
|
// includes k_none servos, which allows those to get their initial
|
||||||
// trim value on startup
|
// trim value on startup
|
||||||
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
|
for (uint8_t i = 0; i < NUM_SERVO_CHANNELS; i++) {
|
||||||
SRV_Channel::Aux_servo_function_t function = (SRV_Channel::Aux_servo_function_t)channels[i].function.get();
|
|
||||||
// see if it is a valid function
|
// see if it is a valid function
|
||||||
if (function < SRV_Channel::k_nr_aux_servo_functions) {
|
if ((uint8_t)channels[i].function.get() < SRV_Channel::k_nr_aux_servo_functions) {
|
||||||
hal.rcout->enable_ch(channels[i].ch_num);
|
hal.rcout->enable_ch(channels[i].ch_num);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user