Skip to content

Commit ededac3

Browse files
committed
AP_NavEKF3: added in a check for high velocity innovation
if using GPS and our horizontal velocity innovation is high then mark the filter as unhealthy, which causes an arming failure this helps with ArduPilot#29384
1 parent a313c2a commit ededac3

File tree

1 file changed

+8
-0
lines changed

1 file changed

+8
-0
lines changed

libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,14 @@ bool NavEKF3_core::healthy(void) const
2828
return false;
2929
}
3030

31+
const float max_vel_innovation = 2.0;
32+
if (onGround && PV_AidingMode == AID_ABSOLUTE &&
33+
frontend->sources.useVelXYSource(AP_NavEKF_Source::SourceXY::GPS) &&
34+
(sq(innovVelPos[0])+sq(innovVelPos[1])) > sq(max_vel_innovation)) {
35+
// more than 2 m/s horizontal velocity innovation on the ground
36+
return false;
37+
}
38+
3139
// all OK
3240
return true;
3341
}

0 commit comments

Comments
 (0)