Copter::pre_arm_rc_checks: fix logic checking that throttle min and max are configured

This commit is contained in:
skyscraper 2016-05-05 19:38:28 +01:00 committed by Randy Mackay
parent 134ea338da
commit 6bcd9e6f65

View File

@ -373,7 +373,7 @@ void Copter::pre_arm_rc_checks()
} }
// check if radio has been calibrated // 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; return;
} }