feat(sensors): barometer thrust compensation with online estimator#26924
feat(sensors): barometer thrust compensation with online estimator#26924dakejahl wants to merge 8 commits into
Conversation
|
You can see the compensation aligns baro with the unfused range data. And from the analysis script we see strong correlation The thrust effect on baro is almost completely removed You can run the baro_thrust_calibration.py script on this log to see the full analysis. |
🔎 FLASH Analysispx4_fmu-v5x [Total VM Diff: 6940 byte (0.34 %)]px4_fmu-v6x [Total VM Diff: 6756 byte (0.35 %)]Updated: 2026-04-02T05:53:55 |
ffb1050 to
98027e9
Compare
|
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-dev-call-apr-01-2026-team-sync-and-community-q-a/48756/2 |
23072a3 to
7c460fc
Compare
Remove SENS_BARO_RATE and SENS_MAG_RATE parameters from the sensor publisher modules (VehicleAirData, VehicleMagnetometer). Sensors now publish at full sensor rate. Add EKF2_BARO_RATE and EKF2_MAG_RATE parameters in the EKF2 module to gate fusion rate on the consumer side. This fixes a rate-aliasing bug where the publish-side rate limiter created irregular sample intervals when the sensor rate was close to the configured limit (e.g. 23Hz baro with 20Hz SENS_BARO_RATE). It also provides full-rate data to the logger and other consumers. Parameter migration translates SENS_BARO_RATE -> EKF2_BARO_RATE and SENS_MAG_RATE -> EKF2_MAG_RATE on import.
7c460fc to
c4596df
Compare
b66880d to
f2f31bf
Compare
|
No broken links found in changed files. |
f2f31bf to
ebfd5b9
Compare
The EKF2 rate limiter was decimating (picking one sample, dropping the rest) which loses the noise reduction that the old publish-side accumulate-and-average provided. Accumulate all incoming samples between fusion intervals and push the average to the EKF instead.
Add propwash-induced barometer error compensation. Propellers create static pressure changes at the baro sensor proportional to motor output. Correction: baro_alt += SENS_BARO_PCOEF * mean_motor_output. Thrust compensation in VehicleAirData uses a motor ring buffer (8 samples) with time-matched lookup against baro timestamp_sample. BMP388 timestamp_sample corrected from read time to integration midpoint (- measurement_time/2), eliminating 38ms baro-thrust lag. Online estimator module (baro_thrust_estimator) uses a complementary filter to isolate thrust-correlated baro error at 0.05Hz crossover, and recursive least squares to identify gain K online. Saves to SENS_BARO_PCOEF on disarm. Controlled by SENS_BAR_AUTOCAL bit 1. SENS_BAR_AUTOCAL migrated from boolean to bitmask (bit 0: GNSS cal, bit 1: thrust comp). Includes offline calibration/validation tool (Tools/baro_compensation/baro_thrust_calibration.py).
…5 Hz Sweep against range-sensor ground truth shows 0.05 Hz produces K estimates that match range K more closely than 0.1 Hz. Update default in firmware, offline analysis tool, and docs.
ec05049 to
c75c9cb
Compare
The instantaneous thrust_std check prevented convergence during gentle hovers where excitation was intermittent but sufficient for RLS to identify K. Track cumulative time above the excitation threshold (5s) instead, so bursts of thrust variation accumulate rather than requiring continuous excitation at the moment of convergence. Validated against flight logs where K estimate was accurate but convergence never triggered due to flickering excitation gate.
The offline CF+RLS replay lacked the firmware's soft guards, so landing dynamics (ground effect, thrust cutoff) corrupted the K estimate. Add velocity (|vz|>2, vxy>5) and range proximity (<0.5m) guards matching the firmware, applied to both the replay and the CF bandwidth sweep.
|
How will it work along the existing baro-airspeed compensation? Will the user have to do the relative airspeed compensation first? Or do you suggest to only use the thrust-baro compensation for multirotors and the airspeed compensation for fixedwings? |
|
Maybe thrust should just add that compensation to the existing baro compensation. Basically, the dynamic baro offset is due to local changes of pressure due to relative airflow, and this airflow is created by the drone's velocity relative to wind (what we compensate for, so far) and prop wash (this PR). You could actually add the thrust component to this cost function in order to distribute the baro errors between drone motion and thrust. And then move the compensation at a common location, either in the EKF or outside (baro compensation dosen't really need to be done inside the EKF backend, it's more a "per-sensor" thing than "per-ekf"). |
| uint64 timestamp # time since system start (microseconds) | ||
| uint64 timestamp_sample # time of baro data last used for this estimate | ||
|
|
||
| float32 residual # CF residual: baro minus accel-predicted altitude [m] | ||
| float32 k_estimate # estimated thrust-to-baro gain [m/unit_thrust] | ||
| float32 k_estimate_var # variance of K estimate (P[0][0]) | ||
| float32 error_var # RLS prediction error variance | ||
| float32 thrust_std # standard deviation of recent thrust excitation | ||
|
|
||
| bool converged # true when all convergence criteria are met | ||
| bool estimation_active # true when RLS is updating (soft guards not active) |
There was a problem hiding this comment.
Needs a short descriptiona and a long description. Below just fixes up the units. I am assuming that the variance has no units.
| uint64 timestamp # time since system start (microseconds) | |
| uint64 timestamp_sample # time of baro data last used for this estimate | |
| float32 residual # CF residual: baro minus accel-predicted altitude [m] | |
| float32 k_estimate # estimated thrust-to-baro gain [m/unit_thrust] | |
| float32 k_estimate_var # variance of K estimate (P[0][0]) | |
| float32 error_var # RLS prediction error variance | |
| float32 thrust_std # standard deviation of recent thrust excitation | |
| bool converged # true when all convergence criteria are met | |
| bool estimation_active # true when RLS is updating (soft guards not active) | |
| uint64 timestamp # [us] ime since system start | |
| uint64 timestamp_sample # [us] Time of baro data last used for this estimate | |
| float32 residual # [m] CF residual: baro minus accel-predicted altitude | |
| float32 k_estimate # [m/unit_thrust] estimated thrust-to-baro gain | |
| float32 k_estimate_var # [-] variance of K estimate (P[0][0]) | |
| float32 error_var # [-] RLS prediction error variance | |
| float32 thrust_std # [-] Standard deviation of recent thrust excitation | |
| bool converged # True when all convergence criteria are met | |
| bool estimation_active # True when RLS is updating (soft guards not active) |
| @@ -0,0 +1,116 @@ | |||
| # Barometer Thrust Compensation | |||
There was a problem hiding this comment.
@dakejahl Good docs - I've prettiered the doc and linked from the parent barometer doc (a good idea because it makes it more accessible in mobile viewers).
Anyway, the one omission that came to my mind is "when should you do this"? Should all vehicles do this?
- What if you have a range sensor - what difference does it make then? I'd "assume" that with a range sensor the baro would be discarded, but maybe this would still be applied and you'd simply have a better fusion of the results?
- It might depend on your configured height reference - GPS, range sensor, baro.
- Where is is great?
Claude also had a few things to say. I don't have opinions about these (except perhaps the first point), but you might:
-
SENS_BAR_AUTOCAL is 1 by default. Worth nothing that baro compensation is disabled by default.
-
"Fly normally for at least 60 seconds" is the guidance but the minimum is 30s. I'm OK with this as a conservative equivalent.
-
No mention of the BMP388 timestamp fix
The PR includes a fix to bmp388.cpp correcting timestamp_sample from read time to integration midpoint (- measurement_time/2), eliminating a 38 ms baro-thrust lag. This is not mentioned in the doc at all. It's
worth a brief note — at minimum as a "known limitation" that other baro drivers (MS5611, DPS310, BMP280) have not yet been corrected and may show residual lag. -
Minor: "the CF residual" explanation could be clearer
The doc says the residual "isolates thrust-correlated pressure error while rejecting real altitude changes." A skeptical reader might ask: why doesn't fast altitude change corrupt the residual? A one-sentence
clarification — "the CF's low crossover frequency (0.05 Hz) means the accelerometer handles all short-timescale altitude changes; residual error accumulates only at timescales longer than ~20 s, where thrust is
the dominant unmodelled signal" — would help.NOTE, I don't think it would help - I prefer your words, but you are the expert.



Summary
Add propwash-induced barometer error compensation. Propellers create static pressure changes at the baro sensor proportional to motor output. On the test vehicle (ARK FPV, BMP390), this causes ~7m altitude error correlated with thrust (r=0.91).
The correction model:
Depends on #26921
Components
Thrust compensation (
VehicleAirData)timestamp_sampleSENS_BARO_PCOEF: altitude correction per unit vertical thrust [m]SENS_BAR_AUTOCALchanged from boolean to bitmask (bit 0: GNSS cal, bit 1: thrust comp)Online estimator (
baro_thrust_estimatormodule)SENS_BARO_PCOEFon disarm when convergedSENS_BAR_AUTOCALbit 1 (started conditionally inrc.mc_apps)Analysis tools (
Tools/baro_compensation/)baro_thrust_calibration.py <log.ulg>— offline calibration/validation with PDF outputParameters
SENS_BARO_PCOEFSENS_BAR_AUTOCALTest results (ARK FPV)
Test plan