mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
AP_NavEKF : Changed timout behaviour to only reset PosVel states
This commit is contained in:
parent
856dfd0ee6
commit
404fbafe26
@ -489,8 +489,12 @@ void NavEKF::UpdateFilter()
|
||||
readIMUData();
|
||||
|
||||
if (dtIMU > 0.2f) {
|
||||
// we have stalled for far too long - reset from DCM
|
||||
InitialiseFilterDynamic();
|
||||
// we have stalled for too long - reset states
|
||||
ResetVelocity();
|
||||
ResetPosition();
|
||||
ResetHeight();
|
||||
//Initialise IMU pre-processing states
|
||||
readIMUData();
|
||||
perf_end(_perf_UpdateFilter);
|
||||
return;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user