EKF Configuration for indoor use

Can one of the EKF developers help me figure out the right configuration for this setup? I’m building a vision-based system that generates position, altitude, heading, vel_xyz, and standard deviations for all of the above. It does not currently generate pitch or roll.

Questions first:

  1. Can the EKF operate with no mag input? How should it be configured for no mag or unreliable mag?

  2. Should the below configuration work?

My plan has been to push all of that information except heading to the EKF via the GPS input, and use the EVData input for yaw.

I think the EKF parameters that need to be modified from the defaults are:

fusion_mode = (1 << 0) | (1 << 6); // GPS, EV Yaw
mag_fusion_type = 5; // None
vdist_sensor_type = 1; // GPS

So to summarize, I’m inputting Accel&Gyro, GPS, EVData (yaw only), and baro into the EKF, although I’d like the baro to be used as little as possible.

For reference, I’ve got the EKF working and flight-capable for outdoor environments with standard sensors (GPS, Mag, IMU, Baro, Airspeed), and am using the defaults for all EKF parameters.

Have you seen this documentation? https://docs.px4.io/v1.9.0/en/advanced_config/tuning_the_ecl_ekf.html

Otherwise, maybe @mhkabir can help…

I have definitely read through that, and this is a request for additional clarification.

One thing that document points out is that a mag is required, although that makes me wonder why this option exists at all (from EKF/common.h):

#define MAG_FUSE_TYPE_NONE 5 ///< Do not use magnetometer under any circumstance. Other sources of yaw may be used if selected via the EKF2_AID_MASK parameter.

Im still trying to read through all of the code to understand how the EKF starts up, but I think it probably requires a mag input at the moment, even if that data will only degrade the solution.

Ok, I don’t know then. I’ll ask Kamil to comment, he has recently looked at that.

As an update to this topic, in Ekf::resetMagHeading(), the following logic exists:

if (_params.mag_fusion_type >= MAG_FUSE_TYPE_NONE) {

return false;
}

Since resetMagheading is called often to set soln_status.flags.attitude, this has the result of the “attitude ok” flag constantly toggling between true and false. I’m not sure if there are any side effects of this like resetting other parts of the estimator, but at the very least it’s filling up my telemetry link and making that attitude flag unusable as an indicator.

So I think this should maybe be a bug report? As it stands I think MAG_FUSE_TYPE_NONE might be unusable.

Let me answer your two questions first:

  1. It seems to me that the EKF is relying on having some mag data for initialization. But however, if you don’t want to use the mag for heading estimation you can provide external orientation information. As you pointed out that would happen if you set the bit for EV_YAW in the EKF_AID_MASK.

  2. Your suggested setup will not work, since the fusion of GPS data and EV_YAW is currently not supported. Since using GPS information makes only sense if you trust your mag to know true north.

Most recent firmware versions (upstream/master) will allow you to send position and velocity data to the EKF via the external vision interface. You can do this by setting the bits for EV_POS and EV_VEL in the EKF_AID_MASK. (You would probably need to upgrade to a new daily build of QGroundcontrol to be able to set the EV_VEL bit).

Sending external position information to FCU raises always the question of the underlying reference coordinate system. How would your reference system be orientated? I assume that its heading is by design of the external system and you are using it presumably indoors, since you don’t want to use the mag. In this case, the EKF reference frame has to be aligned with your reference frame by using your provided heading information. The bad news is that we currently do not support reference frame alignment based on single heading information. At the moment we align the reference frames based on the whole orientation quaternion.

I think that it would make sense to support also the reference frame alignment based on single heading information. I will try to work on this soon.

Can you give me some more information on your setup. How do you plan to send this information to the FCU? With MAVROS?

Hi Kamil, thanks for the detailed response.

Per your #2 point, are you saying that GPS data and EV_YAW are fundamentally incompatible? I would think that any sensor that produces a compass heading would be usable for position/velocity fusion.

I think that the new external vision system in the EKF would be suitable for what I’m doing. I was looking at doing that yesterday, but couldn’t figure out how to set the reference point for the position input, and it’s specified to be local rather than global coordinates. I still think that there’s an issue with a mag being required in that configuration, even when it shouldn’t be used.

Let me explain more about my system. Maybe I’m missing something obvious (has happened before…):

It’s a from-scratch FCS. Me and other students have created all of the hardware drivers and flight control logic, and connect those to the ECL EKF via the methods in estimator_interface.cpp. We’re tracking the upstream master branch of the ECL, and I make sure to pull the latest version and test before posting anything here. We set EKF parameters directly in our cpp file, so qgroundcontrol is out of the loop completely.

My current project is to create a system for indoor navigation. I’ve got an Jetson TX2 that I’ve made to function as the position/heading sensor by using cameras to do a combination of visual marker detection and visual odometry.

Within that system I’m transforming the output into double-precision world coordinates, so that (even though I’m indoors), the system outputs very accurate lat/lon/hdg/vel_ned and altitude agl. This is what I’m trying to send to the EKF.

Regarding the mag, this system would run in areas of high and variable magnetic distortion, so at best the mag would provide no useful heading information. I would like to just get rid of it, through if it’s necessary for attitude fusion, then that may not be an option.

Do you think, given these goals, that there is a configuration for the EKF that will work? Thanks again, Andy

The ECL EKF chooses the reference frame implicitly based on the used heading source. If you want to use the ev_yaw heading the reference frame will be orientated such that its matches the body frame at 0 degree yaw, (and zero pitch and roll of course). Your provided position information should then agree with the EKF reference frame. Meaning that for example if you move your vehicle with 0 degree yaw in forward direction (this is then also x axis of reference frame), your x position measurement should increase, not your y value.
If the reference frame to which you measure the heading does not roughly align with the reference chosen by the EKF, the current implementation of the Kalman Filter will be confused since he will have trouble to align current position and veloctiy information with the heading information.
For this reason if you use GPS the heading should be computed with respect to north. Therefore GPS fusion is not performed when using ev_yaw. See here.

If you can compute the heading angle with respect to the VO reference frame, I would proceed as follows:
Use new EV interface and set ev_sample.pos and ev_sample.vel as well as ev_sample.q together with uncertainty. Build the quaternion from the heading angle, zero pitch and roll should be fine.
Set EKF_AID_MASK bits for EV_YAW, EV_VEL, EV_POS. Your position information should be in your local reference frame (e.g. [0.1,0.3,-0.4]), keep in mind z axis is pointing down.
I would also suggest to use your VO system for primary height: vdist_sensor_type = 3. I think that should do it for you.

I agree for this use case it does not make sense to use the mag for initialization. But as soon as you receive ev_data it will reset the heading to your information, and will stop using the mag at all. See here

Let me know if this works!

It’s working! I’ve got the system set up like you suggested, and implemented a fake mag driver to help the system start up.