EKF2 failed to fuse distance sensor data?

Hello, I am using the optical flow sensor(PMW3901) and distance sensor (TFmini) to control the position. I think I have followed the document to make both sensors work (I can see the correct outputs of both sensor from the MAVLink Inspector). Then I tried to fly it in position mode. The problem is that the local Z is not same with the distance sensor reading, as shown in this log. I am wondering is there anyone who knows how to fix it?
I need the height feedback to do autonomous flying but this wrong feedback keeps me stuck here. Thanks for your time.

What I find weird is that the distance sensor indeed works and contributes to the z-height solution, but not always:

image

I wonder what caused the EKF to stop tracking.

What I find even weirder is why EKF solution tracked the distance sensor reading in the first place, since you have EKF2_RNG_AID=0.

Looks like your sensor reported that its measurements weren’t valid in the first and last part of the flight:
image
This explains the divergence between z-height and measured distance.

It doesn’t explain why distance measurements were used by the EKF since EKF2_RNG_AID=0.

The range finder is set as the primary height source (check EKF2_HGT_MODE)

Right you are. The reason why EKF used range data is the setting of EKF2_HGT_MODE.

In this case, does it mean that invalid range sensor data + EKF2_HGT_MODE=2 leads to an EKF that essentially runs without a absolute height reference (i.e. runs in dead-reckoning)?

Hi Thanks for your reply. I checked the distance sensor (TFmini) I used in px4 firmware. The EKF2 will only use the distance sensor data when it is 0.4m above the ground. In my case, I manually made it take off from the ground. So before 0.4m high, the EKF2 is fusing nothing I think. The reason at 1:10s failed to fuse is that it hit the net frame and fell on the ground. I am wondering how you get the two figures you showed above. And the vehicle_local_position_dist_bottom is also different from my local Z. What plotting tool did you use? How to show the vehicle_local_position_dist_bottom in my log? Thanks.

The tool used is PlotJuggler. You can download a binary executable for Windows or Linux. Load the .ulg file and all UORB topics will be available for plotting.

It actually automatically switches to baro aiding if available (which is the case in this flight):

1 Like

Thanks bresch, I have decided to put a box under the drone before power it on. In that case the distance sensor data is always fused into EKF2. I have another question about the flight, the yaw angle, the setpoint suddenly changed from -30 to -180 (And there are more suddenly changes later). I am sure I didn’t control the yaw at all, and the yaw angle didn’t change significantly. Do you know what’s the possible reason? Thanks

@Haijie_Zhang The first -30 to 180 degrees jump is due to a heading reset done by the EKF after takeoff. This is always performed to avoid issues due to ground magnetic interference. However, in you case, the jump is really large and is apparently due to magnetic interference of the motors/power cables (you can see the correlation between thrust and the magnetometer in the plot below):

The other yaw jumps are just -pi/+pi wraps…

@bresch Thank you very much.

is there anyway in QGC to change the min_distance of distance_sensor !?

No way, the values are hardcoded