Skip to content

New filter for distance sensor validation #24106

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
wants to merge 19 commits into
base: main
Choose a base branch
from

Conversation

haumarco
Copy link
Contributor

@haumarco haumarco commented Dec 13, 2024

Solved Problem

The distance sensor is being fused or used to reset the terrain state, even though its measurements do not accurately represent the distance to the ground due to obstructions caused by rain, snow, fog etc.

Solution

Now the distance sensor can be in 3 different states based on the lpf test ratio of a simple kalman filter: consistent, inconsistent and unknown. A terrain reset can only happen when the state is consistent. The sensor will be used for normal fusion in both consistent and inconsistent states. Together with the already existing fog detector, the robustness against sensor blockage/failure is increased.

new:

new-normal
new-snow
new-blocked

old:

old-normal
old-snow
old-blocked

@haumarco haumarco requested a review from bresch December 13, 2024 13:22
Copy link

github-actions bot commented Dec 13, 2024

🔎 FLASH Analysis

px4_fmu-v5x [Total VM Diff: 1016 byte (0.05 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.1%   +1016  +0.1%   +1016    .text
   +21%    +440   +21%    +440    Ekf::controlRangeHaglFusion()
  +131%    +388  +131%    +388    RangeFinderConsistencyCheck::update()
  [NEW]    +116  [NEW]    +116    RangeFinderConsistencyCheck::evaluateState()
  [NEW]     +64  [NEW]     +64    RangeFinderConsistencyCheck::init()
  +1.4%     +48  +1.4%     +48    Ekf::Ekf()
  +0.0%     +20  +0.0%     +20    g_cromfs_image
  +1.5%     +20  +1.5%     +20    ucdr_serialize_estimator_status_flags()
  +4.8%     +16  +4.8%     +16    EKF2::PublishInnovationTestRatios()
  +4.7%     +16  +4.7%     +16    EKF2::PublishInnovationVariances()
  +4.8%     +16  +4.8%     +16    EKF2::PublishInnovations()
 -99.4%     +16 -99.4%     +16    [6 Others]
  +0.8%      +8  +0.8%      +8    EKF2::PublishStatusFlags()
  +2.1%      +8  +2.1%      +8    Ekf::controlFakeHgtFusion()
  +0.1%      +8  +0.1%      +8    Ekf::predictCovariance()
  +0.0%      +8  +0.0%      +8    [section .text]
  +0.0%      +8  +0.0%      +8    uORB::compressed_fields
  +0.3%      +4  +0.3%      +4    EKF2::AdvertiseTopics()
  -0.2%     -12  -0.2%     -12    Ekf::controlMagFusion()
  -5.5%     -16  -5.5%     -16    Ekf::updateRangeHagl()
  -0.9%     -20  -0.9%     -20    Ekf::fuseMag()
  [DEL]    -140  [DEL]    -140    RangeFinderConsistencyCheck::updateConsistency()
+0.0%     +82  [ = ]       0    .debug_abbrev
+0.0%     +16  [ = ]       0    .debug_aranges
+0.0%    +172  [ = ]       0    .debug_frame
+0.0% +10.0Ki  [ = ]       0    .debug_info
+0.1% +5.42Ki  [ = ]       0    .debug_line
   +33%      +1  [ = ]       0    [Unmapped]
  +0.1% +5.42Ki  [ = ]       0    [section .debug_line]
+0.2% +5.61Ki  [ = ]       0    .debug_loclists
+0.2% +1.30Ki  [ = ]       0    .debug_rnglists
  [DEL]      -1  [ = ]       0    [Unmapped]
  +0.2% +1.31Ki  [ = ]       0    [section .debug_rnglists]
+0.0%    +412  [ = ]       0    .debug_str
-0.4%      -1  [ = ]       0    .shstrtab
+0.0%     +41  [ = ]       0    .strtab
  [NEW]     +52  [ = ]       0    RangeFinderConsistencyCheck::evaluateState()
  [NEW]     +43  [ = ]       0    RangeFinderConsistencyCheck::init()
  +2.1%      +1  [ = ]       0    RangeFinderConsistencyCheck::update()
  [DEL]     -55  [ = ]       0    RangeFinderConsistencyCheck::updateConsistency()
 -43.2%     -16  [ = ]       0    __sq_addafter_veneer
   +67%     +16  [ = ]       0    __uart_connected_veneer
+0.0%     +48  [ = ]       0    .symtab
   +33%     +16  [ = ]       0    EKF2::PublishEventFlags()
  +200%     +32  [ = ]       0    EKF2::PublishInnovationTestRatios()
  +100%     +16  [ = ]       0    EKF2::PublishInnovations()
 -50.0%     -16  [ = ]       0    EKF2::updateParamsImpl()
   +20%     +16  [ = ]       0    Ekf::controlRangeHaglFusion()
 -25.0%     -16  [ = ]       0    Ekf::isYawFailure()
 -50.0%     -16  [ = ]       0    Ekf::resetMagBiasCov()
   +50%     +16  [ = ]       0    Ekf::resetMagEarthCov()
  +100%     +16  [ = ]       0    Ekf::stopMagFusion()
 -66.7%     -32  [ = ]       0    Ekf::updateRangeHagl()
   +33%     +16  [ = ]       0    EstimatorInterface::setSystemFlagData()
  [NEW]     +48  [ = ]       0    RangeFinderConsistencyCheck::evaluateState()
  [NEW]     +48  [ = ]       0    RangeFinderConsistencyCheck::init()
   +33%     +16  [ = ]       0    RangeFinderConsistencyCheck::update()
  [DEL]     -48  [ = ]       0    RangeFinderConsistencyCheck::updateConsistency()
 -33.3%     -32  [ = ]       0    RcvTopicsPubs::init()
 -50.0%     +64  [ = ]       0    [3 Others]
  -0.3%     -32  [ = ]       0    [section .symtab]
 -40.0%     -32  [ = ]       0    __sq_addafter_veneer
 -25.0%     -16  [ = ]       0    __stm32_freesegment_veneer
 -33.3%     -16  [ = ]       0    __stm32_i2c_disable_reload_veneer
-10.3%   -1016  [ = ]       0    [Unmapped]
+0.1% +23.1Ki  +0.0%   +1016    TOTAL

px4_fmu-v6x [Total VM Diff: 984 byte (0.05 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.1%    +984  +0.1%    +984    .text
   +21%    +440   +21%    +440    Ekf::controlRangeHaglFusion()
  +131%    +388  +131%    +388    RangeFinderConsistencyCheck::update()
  [NEW]    +116  [NEW]    +116    RangeFinderConsistencyCheck::evaluateState()
  [NEW]     +64  [NEW]     +64    RangeFinderConsistencyCheck::init()
  +1.4%     +48  +1.4%     +48    Ekf::Ekf()
  +1.5%     +20  +1.5%     +20    ucdr_serialize_estimator_status_flags()
  +4.8%     +16  +4.8%     +16    EKF2::PublishInnovationTestRatios()
  +4.7%     +16  +4.7%     +16    EKF2::PublishInnovationVariances()
  +4.8%     +16  +4.8%     +16    EKF2::PublishInnovations()
 -100.0%     +12 -100.0%     +12    [5 Others]
  +0.8%      +8  +0.8%      +8    EKF2::PublishStatusFlags()
  +2.1%      +8  +2.1%      +8    Ekf::controlFakeHgtFusion()
  +0.1%      +8  +0.1%      +8    Ekf::predictCovariance()
  +0.0%      +8  +0.0%      +8    uORB::compressed_fields
  +0.3%      +4  +0.3%      +4    EKF2::AdvertiseTopics()
  +4.5%      +4  +4.5%      +4    Ekf::resetMagBiasCov()
  -0.7%      -4  -0.7%      -4    Ekf::controlFusionModes()
  -0.2%     -12  -0.2%     -12    Ekf::controlMagFusion()
  -5.5%     -16  -5.5%     -16    Ekf::updateRangeHagl()
  -0.9%     -20  -0.9%     -20    Ekf::fuseMag()
  [DEL]    -140  [DEL]    -140    RangeFinderConsistencyCheck::updateConsistency()
+0.0%     +82  [ = ]       0    .debug_abbrev
+0.0%     +16  [ = ]       0    .debug_aranges
+0.0%    +172  [ = ]       0    .debug_frame
+0.0% +10.0Ki  [ = ]       0    .debug_info
+0.1% +5.42Ki  [ = ]       0    .debug_line
   +50%      +1  [ = ]       0    [Unmapped]
  +0.1% +5.42Ki  [ = ]       0    [section .debug_line]
+0.2% +5.60Ki  [ = ]       0    .debug_loclists
+0.2% +1.30Ki  [ = ]       0    .debug_rnglists
 -66.7%      -2  [ = ]       0    [Unmapped]
  +0.2% +1.31Ki  [ = ]       0    [section .debug_rnglists]
+0.0%    +412  [ = ]       0    .debug_str
+1.3%      +3  [ = ]       0    .shstrtab
+0.0%     +41  [ = ]       0    .strtab
  [NEW]     +52  [ = ]       0    RangeFinderConsistencyCheck::evaluateState()
  [NEW]     +43  [ = ]       0    RangeFinderConsistencyCheck::init()
  +2.1%      +1  [ = ]       0    RangeFinderConsistencyCheck::update()
  [DEL]     -55  [ = ]       0    RangeFinderConsistencyCheck::updateConsistency()
+0.0%     +48  [ = ]       0    .symtab
   +33%     +16  [ = ]       0    EKF2::PublishEventFlags()
  +200%     +32  [ = ]       0    EKF2::PublishInnovationTestRatios()
  +100%     +16  [ = ]       0    EKF2::PublishInnovations()
 -50.0%     -16  [ = ]       0    EKF2::updateParamsImpl()
   +20%     +16  [ = ]       0    Ekf::controlRangeHaglFusion()
 -25.0%     -16  [ = ]       0    Ekf::isYawFailure()
 -50.0%     -16  [ = ]       0    Ekf::resetMagBiasCov()
   +50%     +16  [ = ]       0    Ekf::resetMagEarthCov()
  +100%     +16  [ = ]       0    Ekf::stopMagFusion()
 -66.7%     -32  [ = ]       0    Ekf::updateRangeHagl()
   +33%     +16  [ = ]       0    EstimatorInterface::setSystemFlagData()
  [NEW]     +48  [ = ]       0    RangeFinderConsistencyCheck::evaluateState()
  [NEW]     +48  [ = ]       0    RangeFinderConsistencyCheck::init()
   +33%     +16  [ = ]       0    RangeFinderConsistencyCheck::update()
  [DEL]     -48  [ = ]       0    RangeFinderConsistencyCheck::updateConsistency()
 -33.3%     -32  [ = ]       0    RcvTopicsPubs::init()
  -0.3%     -32  [ = ]       0    [section .symtab]
-12.6%    -984  [ = ]       0    [Unmapped]
+0.1% +23.1Ki  +0.0%    +984    TOTAL

Updated: 2025-05-19T13:01:29

Copy link
Member

@bresch bresch left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm wondering if using sequential fusion would actually give nicer code in the end so you wouldn't need to build all those 2x2 matrices

@haumarco haumarco force-pushed the pr-ekf2_dist_sensor_validation branch 3 times, most recently from 499efdc to f7052d6 Compare December 20, 2024 10:16
@haumarco haumarco marked this pull request as ready for review December 20, 2024 12:06
@haumarco haumarco force-pushed the pr-ekf2_dist_sensor_validation branch 2 times, most recently from 11655eb to 9f42b6e Compare December 20, 2024 12:58
@AlexKlimaj
Copy link
Member

@dakejahl Does this help our height issues?

@haumarco haumarco force-pushed the pr-ekf2_dist_sensor_validation branch from 9f42b6e to 42ea74c Compare December 30, 2024 09:20
@AlexKlimaj
Copy link
Member

AlexKlimaj commented Dec 31, 2024

@haumarco
Copy link
Contributor Author

@AlexKlimaj Your vertical velocity estimate seems to be off quite a lot. Can you increase the bias noise on the acc so the bias will converge a bit quicker? The new filter uses the velocity estimate of the EKF to verify if the measurement is correct or not but when the EKF estimate is off and has a low uncertainty then it will discard the range measurements.

@haumarco haumarco force-pushed the pr-ekf2_dist_sensor_validation branch from 42ea74c to e488ddb Compare January 10, 2025 09:55
@dagar dagar added the EKF2 label Jan 15, 2025
@haumarco haumarco force-pushed the pr-ekf2_dist_sensor_validation branch 2 times, most recently from b0361da to d07902d Compare January 29, 2025 08:32
@@ -268,11 +278,9 @@ void Ekf::updateRangeHagl(estimator_aid_source1d_s &aid_src)

float Ekf::getRngVar() const
{
return fmaxf(
P(State::pos.idx + 2, State::pos.idx + 2)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Good find

@haumarco haumarco force-pushed the pr-ekf2_dist_sensor_validation branch from 5e19f1b to 005510f Compare February 4, 2025 07:59
_time_last_inconsistent_us = time_us;
// start the consistency check after 1s
if (_t_since_first_sample + dt > 1.0f) {
_t_since_first_sample = 2.0f;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Do you really need to force it to 2.0? Maybe remove the +dt in the condition so when it enters the if once, it will always enter it (even if dt is suddenly slightly lower).

@haumarco haumarco force-pushed the pr-ekf2_dist_sensor_validation branch 2 times, most recently from ae44720 to 8946cd2 Compare March 10, 2025 08:47
@haumarco haumarco force-pushed the pr-ekf2_dist_sensor_validation branch from 8946cd2 to 95053b6 Compare April 4, 2025 18:01
@dakejahl
Copy link
Contributor

dakejahl commented Apr 5, 2025

Did a quick flight indoors with the Dexi (Flow, range, and baro. EKF2_HGT_REF=1). Lots of wandering up and down, have to fight with the throttle to keep the altitude in place
https://review.px4.io/plot_app?log=e0095444-5705-490b-82e3-ea1efb4784e5
image

@haumarco
Copy link
Contributor Author

@dakejahl if i replay your log with main it looks pretty much the same. seems like the classic indoor z/vz inconsistency based on suboptimal bias-uncertainties. Or do you have a log where this is not the issue?

@dakejahl
Copy link
Contributor

dakejahl commented Apr 23, 2025

Okay let's take a step back and just focus on outdoor flights.

@haumarco Here's an outdoor flight. EKF replay is enabled in this log. This is based on main from today with this PR and #24751 merged into it.

Dexi airframe (quad)

  • No GPS
  • Distance sensor
  • Optical Flow
  • Barometer

Mostly default params except reduced EKF2_RNG_NOISE to 0.01. So the EKF2_HGT_REF is gps (so it fallbacks to baro), although throughout most of the flight "range aiding" was active, but doesn't appear to work very well since the altitude is fluctuating quite a bit (there was a little bit of wind). I kept the throttle around 0 for most of the flight, for simply testing altitude hold performance. MPC_HOLD_DZ is left at the default of 0.1.

https://review.px4.io/plot_app?log=ddbf2f12-14a9-4400-815c-2520cd347313
Screenshot from 2025-04-22 17-49-22

@DronecodeBot
Copy link

This pull request has been mentioned on Discussion Forum for PX4, Pixhawk, QGroundControl, MAVSDK, MAVLink. There might be relevant details there:

https://discuss.px4.io/t/px4-sync-q-a-april-23-2025/45198/3

@dakejahl
Copy link
Contributor

dakejahl commented May 5, 2025

We should get this in. I've got a branch that improves altitude hold with a rangefinder which is based off of this work.

@dakejahl
Copy link
Contributor

dakejahl commented May 6, 2025

@haumarco can you share the log those screenshots in the description are from? Or any other logs you have of this PR with a distance sensor would be helpful

@dakejahl dakejahl force-pushed the pr-ekf2_dist_sensor_validation branch from 95053b6 to 5659535 Compare May 7, 2025 00:50
@bresch bresch self-requested a review May 19, 2025 08:17
@haumarco haumarco force-pushed the pr-ekf2_dist_sensor_validation branch from 5659535 to 88cb887 Compare May 19, 2025 12:55
KinematicState _state{KinematicState::UNKNOWN};
float _t_since_first_sample{0.f};
uint8_t _last_posD_reset_count{0};
static constexpr float _t_to_init{1.f};
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
static constexpr float _t_to_init{1.f};
static constexpr float _kTestRatioLpfTimeConstant{1.f};

} else if (measurement_idx == 1) {
_innov = y;
const float test_ratio = fminf(sq(y) / (sq(_gate) * S), 4.f); // limit to 4 to limit sensitivity to outliers
_test_ratio_lpf.setParameters(dt, _t_to_init);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

you can set the time constant when declaring the AlphaFilter and then call the update(dt) function

if ((time_us - _time_last_horizontal_motion) > _signed_test_ratio_tau) {
_is_kinematically_consistent = false;
_time_last_inconsistent_us = time_us;
// start the consistency check after 1s
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
// start the consistency check after 1s
// let the filter settle before starting the consistency check

Avoid mentioning numerical values defined elsewhere as ppl will change them without updating the comments

Comment on lines +75 to +76
uint8_t current_posD_reset_count{0};
bool horizontal_motion{false};
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Except if not possible otherwise, member variables should always be private and set/access with setter and getter functions. (and prefixed with _)

@@ -48,36 +48,62 @@ class RangeFinderConsistencyCheck final
RangeFinderConsistencyCheck() = default;
~RangeFinderConsistencyCheck() = default;

void update(float dist_bottom, float dist_bottom_var, float vz, float vz_var, bool horizontal_motion, uint64_t time_us);
enum class KinematicState : int {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.


if (!updated_horizontal_motion && _rng_consistency_check.horizontal_motion) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

the consistency check class itself can trigger the reset when the motion->no_motion transition is detected ("tell don't ask principle": https://martinfowler.com/bliki/TellDontAsk.html)


// AND: an accelerometer with a really large Z bias
const float bias = CONSTANTS_ONE_G;
_sensor_simulator._imu.setAccelData(Vector3f(0.f, 0.f, -CONSTANTS_ONE_G + bias));
_sensor_simulator.runSeconds(2);
_sensor_simulator._imu.setAccelClipping(false, false, true);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Wait, the unit test is to make sure the ekf detect when there is an IMU problem using baro and the range finder, you just changed it to detect the accel clipping flag, this is a different check.

@@ -162,7 +155,7 @@ TEST_F(EkfHeightFusionTest, gpsRef)
_ekf_wrapper.enableBaroHeightFusion();
_ekf_wrapper.enableGpsHeightFusion();
_ekf_wrapper.enableRangeHeightFusion();
_sensor_simulator.runSeconds(1);
_sensor_simulator.runSeconds(10);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Does it just take more time to start the range height fusion now?

@@ -242,7 +235,7 @@ TEST_F(EkfHeightFusionTest, baroRefFailOver)
_ekf_wrapper.enableGpsHeightFusion();
_ekf_wrapper.enableRangeHeightFusion();

_sensor_simulator.runSeconds(0.1);
_sensor_simulator.runSeconds(10);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

100 times slower?

@@ -207,7 +207,7 @@ TEST_F(EkfTerrainTest, testHeightReset)
const float new_baro_height = _sensor_simulator._baro.getData() + 50.f;
_sensor_simulator._baro.setData(new_baro_height);
_sensor_simulator.stopGps(); // prevent from switching to GNSS height
_sensor_simulator.runSeconds(10);
_sensor_simulator.runSeconds(100);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Do you really need 100s? Isn't something broken here?

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
Status: 👀 In review/test
Development

Successfully merging this pull request may close these issues.

6 participants