mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Plane: cope with bad values of ARMING_REQUIRE
This commit is contained in:
parent
43ac3f86c5
commit
5c055220f5
@ -989,20 +989,22 @@ void Plane::set_servos(void)
|
||||
channel_output_mixer(g.elevon_output, channel_pitch->radio_out, channel_roll->radio_out);
|
||||
}
|
||||
|
||||
//send throttle to 0 or MIN_PWM if not yet armed
|
||||
if (!arming.is_armed()) {
|
||||
//Some ESCs get noisy (beep error msgs) if PWM == 0.
|
||||
//This little segment aims to avoid this.
|
||||
switch (arming.arming_required()) {
|
||||
case AP_Arming::YES_MIN_PWM:
|
||||
channel_throttle->radio_out = channel_throttle->radio_min;
|
||||
case AP_Arming::NO:
|
||||
//keep existing behavior: do nothing to radio_out
|
||||
//(don't disarm throttle channel even if AP_Arming class is)
|
||||
break;
|
||||
case AP_Arming::YES_ZERO_PWM:
|
||||
channel_throttle->radio_out = 0;
|
||||
|
||||
case AP_Arming::YES_ZERO_PWM:
|
||||
channel_throttle->radio_out = 0;
|
||||
break;
|
||||
default:
|
||||
//keep existing behavior: do nothing to radio_out
|
||||
//(don't disarm throttle channel even if AP_Arming class is)
|
||||
|
||||
case AP_Arming::YES_MIN_PWM:
|
||||
default:
|
||||
channel_throttle->radio_out = channel_throttle->radio_min;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user