mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_NavEKF2: print reason for EKF2 arming failure when no GPS is available
This commit is contained in:
parent
012ddbefac
commit
1b4705242c
@ -334,6 +334,9 @@ bool NavEKF2_core::InitialiseFilterBootstrap(void)
|
|||||||
{
|
{
|
||||||
// If we are a plane and don't have GPS lock then don't initialise
|
// If we are a plane and don't have GPS lock then don't initialise
|
||||||
if (assume_zero_sideslip() && _ahrs->get_gps().status() < AP_GPS::GPS_OK_FIX_3D) {
|
if (assume_zero_sideslip() && _ahrs->get_gps().status() < AP_GPS::GPS_OK_FIX_3D) {
|
||||||
|
hal.util->snprintf(prearm_fail_string,
|
||||||
|
sizeof(prearm_fail_string),
|
||||||
|
"EKF2 init failure: No GPS lock");
|
||||||
statesInitialised = false;
|
statesInitialised = false;
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user