mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_NavEKF: Reduce EKF start time
Makes EKF start conditional on DCM solution tilt error
This commit is contained in:
parent
5184bca87f
commit
4a5bf0a266
@ -450,8 +450,8 @@ bool NavEKF::healthy(void) const
|
||||
// extremely unhealthy.
|
||||
return false;
|
||||
}
|
||||
// Give the filter 10 seconds to settle before use
|
||||
if ((imuSampleTime_ms - ekfStartTime_ms) < 10000) {
|
||||
// Give the filter a second to settle before use
|
||||
if ((imuSampleTime_ms - ekfStartTime_ms) < 1000 ) {
|
||||
return false;
|
||||
}
|
||||
// barometer innovations must be within limits when on-ground
|
||||
@ -537,6 +537,11 @@ bool NavEKF::InitialiseFilterDynamic(void)
|
||||
return false;
|
||||
}
|
||||
|
||||
// If the DCM solution has not converged, then don't initialise
|
||||
if (_ahrs->get_error_rp() > 0.02f) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// Set re-used variables to zero
|
||||
InitialiseVariables();
|
||||
|
||||
@ -4742,7 +4747,7 @@ void NavEKF::performArmingChecks()
|
||||
{
|
||||
// determine vehicle arm status and don't allow filter to arm until it has been running for long enough to stabilise
|
||||
prevVehicleArmed = vehicleArmed;
|
||||
vehicleArmed = (getVehicleArmStatus() && (imuSampleTime_ms - ekfStartTime_ms) > 10000);
|
||||
vehicleArmed = (getVehicleArmStatus() && (imuSampleTime_ms - ekfStartTime_ms) > 1000);
|
||||
|
||||
// check to see if arm status has changed and reset states if it has
|
||||
if (vehicleArmed != prevVehicleArmed) {
|
||||
|
Loading…
Reference in New Issue
Block a user