-
Notifications
You must be signed in to change notification settings - Fork 14k
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
base: main
Are you sure you want to change the base?
Conversation
🔎 FLASH Analysispx4_fmu-v5x [Total VM Diff: 1016 byte (0.05 %)]
px4_fmu-v6x [Total VM Diff: 984 byte (0.05 %)]
Updated: 2025-05-19T13:01:29 |
There was a problem hiding this 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
src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.cpp
Outdated
Show resolved
Hide resolved
src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.cpp
Outdated
Show resolved
Hide resolved
src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.hpp
Outdated
Show resolved
Hide resolved
src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.cpp
Outdated
Show resolved
Hide resolved
499efdc
to
f7052d6
Compare
11655eb
to
9f42b6e
Compare
src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.cpp
Outdated
Show resolved
Hide resolved
src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.cpp
Outdated
Show resolved
Hide resolved
src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.cpp
Outdated
Show resolved
Hide resolved
src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.cpp
Outdated
Show resolved
Hide resolved
@dakejahl Does this help our height issues? |
9f42b6e
to
42ea74c
Compare
This was a quick indoor flight in manual mode. https://review.px4.io/plot_app?log=e3d3cf76-563d-4a23-9308-d37cbdcd34c3 Vs current main https://review.px4.io/plot_app?log=6d902213-02ef-4ff8-8474-d341bfcc7bd9 |
@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. |
42ea74c
to
e488ddb
Compare
src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.cpp
Outdated
Show resolved
Hide resolved
src/modules/ekf2/EKF/aid_sources/range_finder/range_height_control.cpp
Outdated
Show resolved
Hide resolved
src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.cpp
Outdated
Show resolved
Hide resolved
src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.cpp
Outdated
Show resolved
Hide resolved
src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.cpp
Outdated
Show resolved
Hide resolved
src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.cpp
Outdated
Show resolved
Hide resolved
b0361da
to
d07902d
Compare
@@ -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) |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Good find
src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.hpp
Outdated
Show resolved
Hide resolved
src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.cpp
Outdated
Show resolved
Hide resolved
src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.cpp
Outdated
Show resolved
Hide resolved
src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.cpp
Outdated
Show resolved
Hide resolved
src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.cpp
Outdated
Show resolved
Hide resolved
src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.cpp
Outdated
Show resolved
Hide resolved
src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.cpp
Outdated
Show resolved
Hide resolved
src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.cpp
Outdated
Show resolved
Hide resolved
5e19f1b
to
005510f
Compare
src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.cpp
Outdated
Show resolved
Hide resolved
_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; |
There was a problem hiding this comment.
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).
src/modules/ekf2/EKF/aid_sources/range_finder/range_finder_consistency_check.cpp
Outdated
Show resolved
Hide resolved
ae44720
to
8946cd2
Compare
8946cd2
to
95053b6
Compare
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 |
@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? |
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)
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 |
This pull request has been mentioned on Discussion Forum for PX4, Pixhawk, QGroundControl, MAVSDK, MAVLink. There might be relevant details there: |
We should get this in. I've got a branch that improves altitude hold with a rangefinder which is based off of this work. |
@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 |
95053b6
to
5659535
Compare
* move P-init to ekf-derivation script
…. this fixes behavior for jumps in fixed wing
…n is not defined in test
5659535
to
88cb887
Compare
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}; |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
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); |
There was a problem hiding this comment.
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 |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
// 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
uint8_t current_posD_reset_count{0}; | ||
bool horizontal_motion{false}; |
There was a problem hiding this comment.
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 { |
There was a problem hiding this comment.
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) { |
There was a problem hiding this comment.
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); |
There was a problem hiding this comment.
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); |
There was a problem hiding this comment.
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); |
There was a problem hiding this comment.
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); |
There was a problem hiding this comment.
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?
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
andunknown
. 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:
old: