From 5c055220f52cc241a2b65e4991e0bac03ce47481 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 14 Sep 2015 09:35:53 +1000 Subject: [PATCH] Plane: cope with bad values of ARMING_REQUIRE --- ArduPlane/Attitude.cpp | 18 ++++++++++-------- 1 file changed, 10 insertions(+), 8 deletions(-) diff --git a/ArduPlane/Attitude.cpp b/ArduPlane/Attitude.cpp index c4d1acaa08..02999245c6 100644 --- a/ArduPlane/Attitude.cpp +++ b/ArduPlane/Attitude.cpp @@ -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; } }