From 7173025b432d66ec8a79332e3d75a05d7905b7ff Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 10 Aug 2017 09:14:31 +1000 Subject: [PATCH] AP_Arming: warn about uncalibrated throttle but do not fail check We can tighten this check up later, and will allow us to use this common function for Plane and Rover in the future --- libraries/AP_Arming/AP_Arming.cpp | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index 5730129e4c..e3b431051b 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -600,21 +600,26 @@ bool AP_Arming::rc_checks_copter_sub(const bool display_failure, const RC_Channe } ret = false; } + bool fail = true; if (i == 2) { // skip checking trim for throttle as older code did not check it - continue; + fail = false; } if (channel->get_radio_trim() < channel->get_radio_min()) { if (display_failure) { gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: %s radio trim below min", channel_name); } - ret = false; + if (fail) { + ret = false; + } } if (channel->get_radio_trim() > channel->get_radio_max()) { if (display_failure) { gcs().send_text(MAV_SEVERITY_CRITICAL,"PreArm: %s radio trim above max", channel_name); } - ret = false; + if (fail) { + ret = false; + } } } return ret;