mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
SRV_Channel: fixed set_default_function()
This commit is contained in:
parent
acb5ddd140
commit
77950301ed
@ -451,7 +451,11 @@ void SRV_Channels::set_trim_to_min_for(SRV_Channel::Aux_servo_function_t functio
|
||||
void SRV_Channels::set_default_function(uint8_t chan, SRV_Channel::Aux_servo_function_t function)
|
||||
{
|
||||
if (chan < NUM_SERVO_CHANNELS) {
|
||||
int8_t old = channels[chan].function;
|
||||
channels[chan].function.set_default((uint8_t)function);
|
||||
if (old != channels[chan].function && channels[chan].function == function) {
|
||||
function_mask.set((uint8_t)function);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user