PX4 / PX4-Autopilot

PX4 Autopilot Software
https://px4.io
BSD 3-Clause "New" or "Revised" License
8.2k stars 13.37k forks source link

Lidar Lite (LL40LS) and terrain estimation issues during FW-autoland #9843

Closed philipoe closed 6 years ago

philipoe commented 6 years ago

Issue We use the current master on a fixed-wing plane equipped with a LidarLite v3 (LL40LS driver) connected via I2C. This sensor produces quite some outliers at >15m distance measurement. Unfortunately, the terrain altitude estimator is not robust enough to deal with this. In our case, during a fixed-wing autoland, it estimated that the terrain is at 1m below the airplane and the aircraft flared and nearly forced-off the motor although we were at >=20m AGL. That is obviously dangerous because the airplane can stall at non-recoverable altitude.

Screenshots Distance measurement during the autonomous landing: image

Resulting HAGL test ratio in ekf2 (the fact that this ratio is mostly >1 shows that the terrain estimator actually NEVER trusted the "new" distance sensor measurements) image

Resulting altitude control issues during the autoland. The actual terrain altitude is ~535m AMSL as you can also see on the right of the plot. When the terrain altitude estimate is not drawn then it is considered invalid by the estimator. You can see how the aircraft does the loiter-down on the left side of the plot, and then when it is supposed to enter the final approach it does NOT descend in altitude but flares and even ascends due to having increased its pitch during the flare. image

Flight logs Available at https://review.px4.io/plot_app?log=5e1e86e3-2d9e-4b27-87ff-65f487cbe0ca. This log contains two autolands, the first one which fails as described above and the second one which worked flawlessly.

Analysis

The actual terrain altitude is 535m AMSL. However, during the loiter-down of the autoland (t<2042s) the terrain estimator still thinks that vehicle_altitude ~ terrain_altitude (probably because LL40LS mostly returns 1cm distance when it is out of range). When LL40LS then returns at t=2042s, the HAGL test ratio decreases as expected. But then, unfortunately, the outliers of LL40LS come into play: At t=2045.9, 2055, 2060 etc. LL40LS produces outliers with current_distance=1cm, which makes terrain_estimator think its current belief (i.e. vehicle_alt ~ terrain_alt) is correct and thus resets the terrain variance here. This increases the HAGL test ratio once the true distance measurement comes back again, and thus during the whole autoland the actual distance measurement is never fused into the terrain estimator.

How to fix Of course there is two separate issues: a) The sensor outliers themselves and b) the fact that the terrain estimator is not robust to those. I think we should tackle a) first to not need to add arbitrary filtering to b) / the terrain estimator.

So to everybody who was involved in the LL40LS driver development, i.e. @Zefz @bansiesta, do you have an immediate clue of where those outliers are coming from (note that they are always 1cm!). Is this an issue with the driver or the sensor itself? In the latter case we could think about integrating outlier rejection...

@antiheavy @ryanjAA @tstastny FYI

ryanjAA commented 6 years ago

I’ll be back in the office this evening and can provide some nore but we experienced the same thing with the ll2 and v3. Essentially we look at the useful range of the unit at no more than 15m and I think if I look back we averaged it at 12m given anything past that was useless. The quick fix is have outlier reading go beyond the driver so it’s recognized as false for estimation or on the other hand set the min reading parameter above 1cm so estimation knows it’s false.

As for the terrain estimator - we are on the same page. We opened an issue a year+ back about this since I couldn’t agree more it’s simply not robust enough and when you think about it logically and not from an estimation perspective, there is no way you can have a truthful measurement go from x measurement to 1 cm unless speed is y (ie very large). Therefor it should be false and disregarded but the issue mostly in the hardware. It doesn’t provide accurate readings past that range and then on the driver side it is simply how that is handled. The driver was changed months back to lower the effective range of measurements but I don’t think that really helps. It needs to be something more. On consistent data in line with other data sources a simple lpf over the lidar data would smooth it out a bit but I’d say 99% of planes we ship don’t use that sensor anymore just because it simply only has that 12-15m effective range and when you are in your second to last landing waypoint and you terrain estimator is looking for lidar data, generally you are much higher than 12-15m to have a good and accurate plan for ideal slope. We had (years back during some testing, pre settings and drivers changed), a flare at 50m and that ended wonderfully........ all because of terrain estimator and the lidar measurement. That probably wouldn’t have happened today given the difference in code at the time but still, the fact you are seeing issues means the driver should have a look over (the sfxx series lidars let you set what you want the out of range measurements to be on the unit itself which is a much better approach when you don’t have software control from the firmware side) and the terrain estimator needs a big overhaul. I’ll find my notes on that.

ryanjAA commented 6 years ago

Take a look at #6456 and 9262

As for HAGL and acceptance, I'll take a look at some logs on file here, I know I've seen it exclude good data and exclude bad data but the majority of issues were fixed the easy way which was using a better lidar which is not the answer. If we were allowed to fly 200m agl all day every day we would have the same or similar issue as with the LL2/3 so at some point we will see the same thing happening again which means a true fix is needed.

Take a look at the attached image. Baro and lidar are scaled down by 10 to see and HAGL ration up by 10 for clarity but the sensor is set to output 130m when no reading comes in. We see it working more than not working since all under 10 except for that first false lidar data report but then on the second one (~3250), it works correctly. If looking at this, one thing is clear, it does not like pitching. Almost all cases of of spikes in the HAGL ratio are which pitching up or down which I guess make sense to some extent although i dont know why we dont just calculate the distance above the ground given the measured distance and the angle of the plane as a right angle but here nor there right now.

1

LorenzMeier commented 6 years ago

@priseborough Could you please have a look as well?

philipoe commented 6 years ago

I submitted a PR for much better filtering of LL40LS's data at https://github.com/PX4/Firmware/pull/9865 . This seems to greatly improve the quality of the data I am getting. It also involves a one-liner change to ekf2_main, so yes, it would be great if you @priseborough could quickly check that.

priseborough commented 6 years ago

We would also benefit from reducing the process noise that is applied to the terrain height state. The innovation variance is growing too quickly when innovation consistency checks fail.

Something I have seen with sonar based distance sensors is faulty readings are normally accompanied by large and rapid variation in reading. Running a real time noise variance calculation within the sensor driver with a max threshold enables bad data to be rejected before it is used by the estimators. In combination with a median filter, this seems to work on replay with a multi rotor data set.

I am resisting putting in sensor type specific threshold checks into the estimator because this will end up with multiple checks to handle the failure mechanisms for different sensor types. My preference is that the validity of sensor specific metrics such as noise variance, S/N ratio, etc is not done by the EKF. The sensor driver has access to full rate data and where estimator agnostic validity checking using pre-filtered and down-sampled data is achievable, it should be done in the sensor driver.

See https://github.com/PX4/Firmware/issues/9861 for some additional changes we need to make to the covariance message.

Antiheavy commented 6 years ago

interesting topic. we've just started testing the TFmini "12 meter" sensor but don't have any flight results yet. It's pretty short range so we are mostly hoping for more accurate flare.

jinchengde commented 6 years ago

we had test TFMini '12 meter', set the lidar work below 5 meters for autoland the flight log is https://review.px4.io/plot_app?log=c566fe21-2b0d-4e06-8082-03c031198c4f and in EKF ecl analysis, we could see rangefind aid default

priseborough commented 6 years ago

@philipoe The change has been merged.