mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
Copter::pre_arm_rc_checks: fix logic checking that throttle min and max are configured
This commit is contained in:
parent
134ea338da
commit
6bcd9e6f65
@ -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;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user