mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
Copter: use prearm_failure_reason()
This commit is contained in:
parent
c4d561a4eb
commit
7ca88a26da
@ -646,7 +646,12 @@ bool Copter::pre_arm_gps_checks(bool display_failure)
|
||||
// ensure GPS is ok
|
||||
if (!position_ok()) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Need 3D Fix"));
|
||||
const char *reason = ahrs.prearm_failure_reason();
|
||||
if (reason) {
|
||||
GCS_MAVLINK::send_statustext_all(SEVERITY_HIGH, PSTR("PreArm: %s"), reason);
|
||||
} else {
|
||||
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Need 3D Fix"));
|
||||
}
|
||||
}
|
||||
AP_Notify::flags.pre_arm_gps_check = false;
|
||||
return false;
|
||||
|
Loading…
Reference in New Issue
Block a user