mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
AP_Arming: move ahrs health check after Accel/Gyro checks
If the AHRS is unhealthy because of accel or gyro problems we want those underlying problem reported first
This commit is contained in:
parent
0a21fe65e9
commit
f5f31e4b31
@ -142,12 +142,6 @@ bool AP_Arming::ins_checks(bool report)
|
||||
}
|
||||
return false;
|
||||
}
|
||||
if (!ahrs.healthy()) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: AHRS not healthy"));
|
||||
}
|
||||
return false;
|
||||
}
|
||||
if (!ins.accel_calibrated_ok_all()) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: 3D accel cal needed"));
|
||||
@ -206,6 +200,12 @@ bool AP_Arming::ins_checks(bool report)
|
||||
}
|
||||
}
|
||||
#endif
|
||||
if (!ahrs.healthy()) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: AHRS not healthy"));
|
||||
}
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
return true;
|
||||
|
Loading…
Reference in New Issue
Block a user