mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Copter: use accel_calibrated_ok_all
This commit is contained in:
parent
1f14eec4ea
commit
ae87f9be6e
@ -393,9 +393,9 @@ static bool pre_arm_checks(bool display_failure)
|
|||||||
// check INS
|
// check INS
|
||||||
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_INS)) {
|
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_INS)) {
|
||||||
// check accelerometers have been calibrated
|
// check accelerometers have been calibrated
|
||||||
if(!ins.calibrated()) {
|
if(!ins.accel_calibrated_ok_all()) {
|
||||||
if (display_failure) {
|
if (display_failure) {
|
||||||
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: INS not calibrated"));
|
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Accels not calibrated"));
|
||||||
}
|
}
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user