mirror of https://github.com/ArduPilot/ardupilot
Copter: fix mode and fence gps check fail message
This commit is contained in:
parent
ebd2e15a6e
commit
8ce27afba0
|
@ -523,24 +523,23 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure)
|
||||||
fence_requires_gps = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;
|
fence_requires_gps = (copter.fence.get_enabled_fences() & (AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)) > 0;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// return true if GPS is not required
|
if (mode_requires_gps) {
|
||||||
if (!mode_requires_gps && !fence_requires_gps) {
|
if (!copter.position_ok()) {
|
||||||
return true;
|
// There is no need to call prearm_failure_reason again, because prearm_healthy sure be true if we reach here
|
||||||
}
|
check_failed(display_failure, "Need 3D Fix");
|
||||||
|
return false;
|
||||||
// ensure GPS is ok
|
}
|
||||||
if (!copter.position_ok()) {
|
} else {
|
||||||
const char *reason = ahrs.prearm_failure_reason();
|
if (fence_requires_gps) {
|
||||||
if (reason == nullptr) {
|
if (!copter.position_ok()) {
|
||||||
if (!mode_requires_gps && fence_requires_gps) {
|
// clarify to user why they need GPS in non-GPS flight mode
|
||||||
// clarify to user why they need GPS in non-GPS flight mode
|
check_failed(display_failure, "Fence enabled, need 3D Fix");
|
||||||
reason = "Fence enabled, need 3D Fix";
|
return false;
|
||||||
} else {
|
}
|
||||||
reason = "Need 3D Fix";
|
} else {
|
||||||
}
|
// return true if GPS is not required
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
check_failed(display_failure, "%s", reason);
|
|
||||||
return false;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// check for GPS glitch (as reported by EKF)
|
// check for GPS glitch (as reported by EKF)
|
||||||
|
|
Loading…
Reference in New Issue