mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
AP_NavEKF3: Remove unwanted line
This commit is contained in:
parent
2565f3917c
commit
4b88b2ccec
@ -711,7 +711,6 @@ void NavEKF3_core::FuseVelPosNED()
|
|||||||
// Always fuse data if bad IMU to prevent aliasing and clipping pulling the state estimate away
|
// Always fuse data if bad IMU to prevent aliasing and clipping pulling the state estimate away
|
||||||
// from the measurement un-opposed if test threshold is exceeded.
|
// from the measurement un-opposed if test threshold is exceeded.
|
||||||
if (posCheckPassed || posTimeout || badIMUdata) {
|
if (posCheckPassed || posTimeout || badIMUdata) {
|
||||||
posCheckPassed = true;
|
|
||||||
lastPosPassTime_ms = imuSampleTime_ms;
|
lastPosPassTime_ms = imuSampleTime_ms;
|
||||||
// if timed out or outside the specified uncertainty radius, reset to the external sensor
|
// if timed out or outside the specified uncertainty radius, reset to the external sensor
|
||||||
if (posTimeout || ((P[8][8] + P[7][7]) > sq(float(frontend->_gpsGlitchRadiusMax)))) {
|
if (posTimeout || ((P[8][8] + P[7][7]) > sq(float(frontend->_gpsGlitchRadiusMax)))) {
|
||||||
|
Loading…
Reference in New Issue
Block a user