mirror of https://github.com/ArduPilot/ardupilot
Copter: add arming check for compass calibration running
This commit is contained in:
parent
3739318d2f
commit
fa6bfee433
|
@ -735,6 +735,13 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
|||
return false;
|
||||
}
|
||||
|
||||
if(compass.is_calibrating()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Compass calibration running"));
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
// always check if the current mode allows arming
|
||||
if (!mode_allows_arming(control_mode, arming_from_gcs)) {
|
||||
if (display_failure) {
|
||||
|
|
Loading…
Reference in New Issue