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);
|
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()) {
|
if (!arming.is_armed()) {
|
||||||
//Some ESCs get noisy (beep error msgs) if PWM == 0.
|
//Some ESCs get noisy (beep error msgs) if PWM == 0.
|
||||||
//This little segment aims to avoid this.
|
//This little segment aims to avoid this.
|
||||||
switch (arming.arming_required()) {
|
switch (arming.arming_required()) {
|
||||||
case AP_Arming::YES_MIN_PWM:
|
case AP_Arming::NO:
|
||||||
channel_throttle->radio_out = channel_throttle->radio_min;
|
//keep existing behavior: do nothing to radio_out
|
||||||
|
//(don't disarm throttle channel even if AP_Arming class is)
|
||||||
break;
|
break;
|
||||||
case AP_Arming::YES_ZERO_PWM:
|
|
||||||
channel_throttle->radio_out = 0;
|
case AP_Arming::YES_ZERO_PWM:
|
||||||
|
channel_throttle->radio_out = 0;
|
||||||
break;
|
break;
|
||||||
default:
|
|
||||||
//keep existing behavior: do nothing to radio_out
|
case AP_Arming::YES_MIN_PWM:
|
||||||
//(don't disarm throttle channel even if AP_Arming class is)
|
default:
|
||||||
|
channel_throttle->radio_out = channel_throttle->radio_min;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user