mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
RC_Channel: don't force radio_out in enable_aux_servos()
this is called regularly, and causes the servo to twitch
This commit is contained in:
parent
ccf8ba3ce9
commit
7b4dc246f8
@ -87,7 +87,6 @@ enable_aux_servos()
|
||||
RC_Channel_aux::Aux_servo_function_t function = (RC_Channel_aux::Aux_servo_function_t)_aux_channels[i]->function.get();
|
||||
// see if it is a valid function
|
||||
if (function < RC_Channel_aux::k_nr_aux_servo_functions) {
|
||||
_aux_channels[i]->radio_out = _aux_channels[i]->radio_trim;
|
||||
_aux_channels[i]->enable_out();
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user