Skip to content

EKF3 velocity divergence pre-arm #29384

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
tridge opened this issue Feb 27, 2025 · 4 comments
Open

EKF3 velocity divergence pre-arm #29384

tridge opened this issue Feb 27, 2025 · 4 comments
Assignees

Comments

@tridge
Copy link
Contributor

tridge commented Feb 27, 2025

We had a divergence of EKF3 velocity pre-arming on the ground which caused a roll over on takeoff of a quadplane.
GPS velocity looks fine, EKF3 velocity is very bad. Normalised innovations were low.
Replay log here:
http://uav.tridgell.net/tmp/00000082.BIN
replays nicely, no log packet loss
firmware is 4.6.0-beta4, but master replay shows the same issue.

old versions tested:

  • 4.5.7 gives same replay result
  • 4.4.4 gives the same replay result
  • 4.3.8 gives almost the same result (same general VE divergence)
  • 4.2.3 reproduces the issue
  • the 4.1.x replay doesn't work with the log

you can use replay with EKF2 on this log with this PR:
#29405
and --force-ekf2
Using EKF2 the velocity does not diverge, so this looks to be an EKF3 only issue, and one that has been in EKF3 for a very long time

Apart from the divergence, the other worrying part of this log is that the scaled innovations presented to the EKF failsafe code and to the user over MAVLink do not show any health issues with the EKF. Same goes for the lane switching error scores. So no fail-safes, no GCS warnings, no arming check failures.

Other notes:

  • delaying the start of GPS fusion in EKF3 to be after 90s of stability in NavEKF3_core::calcGpsGoodToAlign() instead of 10s "fixes" the issue

Image

Image

update:

@tridge
Copy link
Contributor Author

tridge commented Feb 27, 2025

V09 is diverging (vertical position variance, note it is using GPS for vertical position)

Image

@tridge
Copy link
Contributor Author

tridge commented Feb 27, 2025

the V05 (variance of velocity east) is diverging badly:
Image
it is stopping at 1000.0, which comes from NavEKF3_core::ConstrainVariances()

@priseborough
Copy link
Contributor

Replay of the log with EK3_MAG_CAL=4 (always use 3-axis fusion) eliminates the instability so I am now investigating the yaw fusion process.

@timtuxworth
Copy link
Contributor

timtuxworth commented Mar 3, 2025

I don't know if this is related, but I had a strange rollover on auto takeoff on a Fixed Wing yesterday. One thing I noticed is that it was pointing almost directly North just before the takeoff. This was on a very recent master.

https://www.dropbox.com/scl/fi/grw2cn5ru0329j50gzck7/log_13_2025-3-2-18-10-36.bin?rlkey=xz8u3f6y64nun5ui4hu06euiy&dl=0

This is the previous flight with the same plane. The only change was a new battery:
https://www.dropbox.com/scl/fi/untspenoeugrf7g71wylg/log_12_2025-3-2-18-01-36.bin?rlkey=jqk3ywukkiv7l6jiyom51pps3&dl=0

Sorry if this is not related.

tridge added a commit to tridge/ardupilot that referenced this issue Mar 5, 2025
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
tridge added a commit to tridge/ardupilot that referenced this issue Mar 7, 2025
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
tridge added a commit to tridge/ardupilot that referenced this issue Mar 11, 2025
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
rmackay9 pushed a commit that referenced this issue Mar 12, 2025
if using GPS and our horizontal velocity innovation is high then mark
the filter as unhealthy, which causes an arming failure

this helps with #29384
rmackay9 pushed a commit to rmackay9/rmackay9-ardupilot that referenced this issue Mar 31, 2025
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
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
Status: No status
Development

No branches or pull requests

3 participants