mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Copter: use configured to check whether radio has been calibrated
This commit is contained in:
parent
21e7d46944
commit
28f55766fd
@ -567,7 +567,7 @@ void Copter::pre_arm_rc_checks()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// check if radio has been calibrated
|
// check if radio has been calibrated
|
||||||
if(!channel_throttle->radio_min.load() && !channel_throttle->radio_max.load()) {
|
if(!channel_throttle->radio_min.configured() && !channel_throttle->radio_max.configured()) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user