From 6bcd9e6f65b43c3bfa0554b81ff764e0030159aa Mon Sep 17 00:00:00 2001 From: skyscraper Date: Thu, 5 May 2016 19:38:28 +0100 Subject: [PATCH] Copter::pre_arm_rc_checks: fix logic checking that throttle min and max are configured --- ArduCopter/arming_checks.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/arming_checks.cpp b/ArduCopter/arming_checks.cpp index c93699bcaf..d4737cb360 100644 --- a/ArduCopter/arming_checks.cpp +++ b/ArduCopter/arming_checks.cpp @@ -373,7 +373,7 @@ void Copter::pre_arm_rc_checks() } // check if radio has been calibrated - if (!channel_throttle->radio_min.configured() && !channel_throttle->radio_max.configured()) { + if (!channel_throttle->radio_min.configured() || !channel_throttle->radio_max.configured()) { return; }