mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
AP_Arming: do not report prearm_failure_reason when ahrs unhealthy
The EKF's prearm failiure message is more related to the position estimate rather than the ahrs's health
This commit is contained in:
parent
78c6287f95
commit
0a21fe65e9
@ -144,12 +144,7 @@ bool AP_Arming::ins_checks(bool report)
|
||||
}
|
||||
if (!ahrs.healthy()) {
|
||||
if (report) {
|
||||
const char *reason = ahrs.prearm_failure_reason();
|
||||
if (reason) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: %s"), reason);
|
||||
} else {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: AHRS not healthy"));
|
||||
}
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, PSTR("PreArm: AHRS not healthy"));
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user