EKF2 GPS fusion without heading source

About

As of currently in PX4, I found that the GPS fusion wonā€™t start in EKF2 unless there are one of the following heading estimate sources:

  • Dual antenna GPS for heading information
  • External Vision
  • Magnetometer

We were interested in a way to allow GPS fusion even without heading estimate sensor because we wanted to exclude using magnetometer for simplifying the sensor set used onboard a flying wing, intended for navigating to coordinates.

Hereā€™s a log for the test where EKF2 was not able to provide global position estimate, as the GPS fusion was not happening: https://logs.px4.io/plot_app?log=1395a014-1397-4e84-91f2-c8227785a315

:point_up: By the way, the EKF2 logged flags, events, statues were super helpful, and the ECL EKF documentation helped me so much, super awesome!

EKF-GSF use case

I do think that yes, starting EKF2 GPS fusion without an heading estimate is a bad idea, we should also be able to do that, and I ā€˜thinkā€™ EKF2 should be able to converge to a sane heading estimate.

And a similar feature is already implemented in the EKF-GSF, documented here: Using the ECL EKF | PX4 User Guide (main)

However, the EKF-GSF only runs as a ā€˜fallbackā€™ mechanism, after the vehicle is already armed (which is only possible when vehicle has global position estimate, which in turn is only possible when GPS fusion is possible, which means as of right now, the user had to have a heading estimate sensor onboard) and in air, to handle heading sensor issues:

:question: Question

Would it be ok for EKF2 to just bypass having heading estimate, and do the GPS fusion? (corresponding to filter yaw alignment control state: PX4-Autopilot/src/modules/ekf2/EKF/common.h at 95b30056794b47bb415f4c1d96028ec77a567446 Ā· PX4/PX4-Autopilot Ā· GitHub)

Or, is there a way to tell EKF2 that we do not wish to have any heading reference (magnetometer, even EKF-GSF itself), and just have heading estimated completely from the GPS track & IMU (decoupled from the EKF-GSF itself)?

Implementation

For example, bypassing yaw alignment requirement would look something like removing the if condition, and setting mandatory_conditions_passing to true:

When I run the simulation with that change & set ā€œSENS_EN_MAGSIMā€ (disable simulated magnetometer) to 0 & ā€œSYS_HAS_MAGā€ to 0 (to enable preflight check to pass), I can verify that vehicle can run as expected & do loiter as the EKF-GSF takes over (ā€œyaw_estimator_statusā€ message is being published):

Suggestion

Apart from my question on this topic, as noted in my recent post, I think that having a more verbose error output such as:

No yaw_align fusion is happening, need external heading sensors for GPS fusion to start

would have been really helpful to figure out why:

No valid global position estimate available

error was popping up (and we forgot about having turned off the magnetometer).

So may be worth adding this message? Perhaps here:

1 Like

this would cause ā€œno valid local position estimateā€ as well, right?

Iā€™ve just spent a day trying to troubleshoot this, so yes, that would be a great feature ā€“ both support for missing compass and better EKF-related errors

It does not even need to be in the UI, just putting more information into estimator_aid_src_gnss_pos messages would already be great, I think currently many EKF issues are not published anywhere?

1 Like

This is a great topic, I am interested how did it end?