Skip to content

feat(sensors): barometer thrust compensation with online estimator#26924

Open
dakejahl wants to merge 8 commits into
mainfrom
dakejahl/baro-thrust-estimator-pr
Open

feat(sensors): barometer thrust compensation with online estimator#26924
dakejahl wants to merge 8 commits into
mainfrom
dakejahl/baro-thrust-estimator-pr

Conversation

@dakejahl
Copy link
Copy Markdown
Contributor

@dakejahl dakejahl commented Apr 1, 2026

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:

baro_alt += SENS_BARO_PCOEF * thrust_z

Depends on #26921

Components

Thrust compensation (VehicleAirData)

  • Motor thrust ring buffer (8 samples) with time-matched lookup against baro timestamp_sample
  • Param SENS_BARO_PCOEF: altitude correction per unit vertical thrust [m]
  • SENS_BAR_AUTOCAL changed from boolean to bitmask (bit 0: GNSS cal, bit 1: thrust comp)

Online estimator (baro_thrust_estimator module)

  • Complementary filter (CF) isolates thrust-correlated baro error at 0.05 Hz crossover
  • Recursive least squares (RLS) identifies gain K online
  • Saves identified coefficient to SENS_BARO_PCOEF on disarm when converged
  • Controlled by SENS_BAR_AUTOCAL bit 1 (started conditionally in rc.mc_apps)

Analysis tools (Tools/baro_compensation/)

  • baro_thrust_calibration.py <log.ulg> — offline calibration/validation with PDF output

Parameters

Parameter Default Description
SENS_BARO_PCOEF 0.0 Baro alt correction per unit thrust [m]
SENS_BAR_AUTOCAL 1 Bitmask: bit 0 = GNSS cal, bit 1 = thrust comp

Test results (ARK FPV)

  • K ≈ -20 to -22m consistent across flights, online/offline agree within 0.5m
  • Compensation: thrust correlation r from 0.91 → 0.16, error std from 2.3m → 0.95m
  • BMP390 integration window (37ms) smooths over motor response (~15ms), no delay param needed

Test plan

  • Flight test with SENS_BARO_PCOEF=0 (disabled) — verify no regression
  • Flight test with online estimation enabled — verify convergence
  • Compare before/after EKF baro innovation statistics

@dakejahl
Copy link
Copy Markdown
Contributor Author

dakejahl commented Apr 1, 2026

You can see the compensation aligns baro with the unfused range data.
https://review.px4.io/plot_app?log=30784ce8-1901-4e10-b62c-39d117a03f2c
image

And from the analysis script we see strong correlation
image

The thrust effect on baro is almost completely removed
image

You can run the baro_thrust_calibration.py script on this log to see the full analysis.

@github-actions
Copy link
Copy Markdown

github-actions Bot commented Apr 1, 2026

🔎 FLASH Analysis

px4_fmu-v5x [Total VM Diff: 6940 byte (0.34 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.3% +6.76Ki  +0.3% +6.76Ki    .text
  [NEW] +1.33Ki  [NEW] +1.33Ki    BaroThrustEstimator::Run()
 -99.0%    +712 -99.0%    +712    [73 Others]
  +0.4%    +652  +0.4%    +652    [section .text]
  [NEW]    +516  [NEW]    +516    BaroThrustEstimator::BaroThrustEstimator()
  +0.2%    +388  +0.2%    +388    g_cromfs_image
  [NEW]    +376  [NEW]    +376    BaroThrustCfRls::checkConvergence()
  [NEW]    +340  [NEW]    +340    BaroThrustCfRls::RlsEstimator::update()
  [NEW]    +316  [NEW]    +316    BaroThrustEstimator::saveParameters()
  [NEW]    +296  [NEW]    +296    BaroThrustEstimator::~BaroThrustEstimator()
   +72%    +204   +72%    +204    EKF2::UpdateMagSample()
  [NEW]    +192  [NEW]    +192    sensors::VehicleAirData::thrustCompensation()
  [NEW]    +188  [NEW]    +188    BaroThrustCfRls::updateEstimator()
  [NEW]    +180  [NEW]    +180    BaroThrustEstimator::print_status()
  [NEW]    +172  [NEW]    +172    BaroThrustCfRls::updateCf()
   +65%    +164   +65%    +164    EKF2::UpdateBaroSample()
  [NEW]    +160  [NEW]    +160    BaroThrustCfRls::computeAccelUp()
  [NEW]    +156  [NEW]    +156    BaroThrustEstimator::publishStatus()
   +14%    +156   +14%    +156    param_modify_on_import()
  [NEW]    +136  [NEW]    +136    BaroThrustEstimator::task_spawn()
  [NEW]    +128  [NEW]    +128    BaroThrustEstimator::init()
  [NEW]    +124  [NEW]    +124    sensors::VehicleAirData::updateThrustBuffer()
+0.1%     +16  +0.1%     +16    .ramfunc
   +20%      +4   +20%      +4    get_orb_meta()
  +1.7%      +4  +1.7%      +4    param_get
  +1.4%      +4  +1.4%      +4    param_get_default_value
   +33%      +4   +33%      +4    param_get_index
  +9.1%      +4  +9.1%      +4    param_get_system_default_value
   +14%      +1   +14%      +1    ___ZN4ListIP13MavlinkStreamE8IteratorppEv.isra.0_veneer
 -12.5%      -1 -12.5%      -1    __up_restoreusartint_veneer
  -1.2%      -4  -1.2%      -4    Ekf::measurementUpdate()
+1.0%      +4  +1.0%      +4    .init_section
+0.3% +6.12Ki  [ = ]       0    .debug_abbrev
+0.2%    +400  [ = ]       0    .debug_aranges
+0.3% +1.36Ki  [ = ]       0    .debug_frame
+0.4%  +112Ki  [ = ]       0    .debug_info
+0.3% +17.5Ki  [ = ]       0    .debug_line
  [NEW]      +1  [ = ]       0    [Unmapped]
  +0.3% +17.5Ki  [ = ]       0    [section .debug_line]
+0.3% +11.9Ki  [ = ]       0    .debug_loclists
+0.4% +2.49Ki  [ = ]       0    .debug_rnglists
  [DEL]      -2  [ = ]       0    [Unmapped]
  +0.4% +2.49Ki  [ = ]       0    [section .debug_rnglists]
+0.2% +6.12Ki  [ = ]       0    .debug_str
-0.8%      -2  [ = ]       0    .shstrtab
+0.2% +1.32Ki  [ = ]       0    .strtab
  [NEW]     +43  [ = ]       0    BaroThrustCfRls::RlsEstimator::reset()
  [NEW]     +47  [ = ]       0    BaroThrustCfRls::RlsEstimator::update()
  [NEW]     +42  [ = ]       0    BaroThrustCfRls::checkConvergence()
  [NEW]     +82  [ = ]       0    BaroThrustCfRls::computeAccelUp()
  [NEW]     +29  [ = ]       0    BaroThrustCfRls::reset()
  [NEW]     +34  [ = ]       0    BaroThrustCfRls::updateCf()
  [NEW]     +42  [ = ]       0    BaroThrustCfRls::updateEstimator()
  [NEW]     +26  [ = ]       0    BaroThrustEstimator
  [NEW]     +58  [ = ]       0    BaroThrustEstimator::BaroThrustEstimator()
  [NEW]     +68  [ = ]       0    BaroThrustEstimator::Run()
  [NEW]     +46  [ = ]       0    BaroThrustEstimator::custom_command()
  [NEW]     +32  [ = ]       0    BaroThrustEstimator::init()
  [NEW]     +41  [ = ]       0    BaroThrustEstimator::print_status()
  [NEW]     +42  [ = ]       0    BaroThrustEstimator::print_usage()
  [NEW]     +44  [ = ]       0    BaroThrustEstimator::publishStatus()
  [NEW]     +43  [ = ]       0    BaroThrustEstimator::saveParameters()
  [NEW]     +42  [ = ]       0    BaroThrustEstimator::task_spawn()
  [NEW]     +87  [ = ]       0    BaroThrustEstimator::updateParams()
  [NEW]     +95  [ = ]       0    BaroThrustEstimator::updateParamsImpl()
  [NEW]    +225  [ = ]       0    BaroThrustEstimator::~BaroThrustEstimator()
 -99.4%    +186  [ = ]       0    [9 Others]
+0.3% +1.64Ki  [ = ]       0    .symtab
  [NEW]     +48  [ = ]       0    BaroThrustCfRls::RlsEstimator::reset()
  [NEW]     +48  [ = ]       0    BaroThrustCfRls::RlsEstimator::update()
  [NEW]     +48  [ = ]       0    BaroThrustCfRls::checkConvergence()
  [NEW]     +64  [ = ]       0    BaroThrustCfRls::computeAccelUp()
  [NEW]     +48  [ = ]       0    BaroThrustCfRls::reset()
  [NEW]     +48  [ = ]       0    BaroThrustCfRls::updateCf()
  [NEW]     +48  [ = ]       0    BaroThrustCfRls::updateEstimator()
  [NEW]     +32  [ = ]       0    BaroThrustEstimator
  [NEW]     +64  [ = ]       0    BaroThrustEstimator::BaroThrustEstimator()
  [NEW]    +112  [ = ]       0    BaroThrustEstimator::Run()
  [NEW]     +64  [ = ]       0    BaroThrustEstimator::custom_command()
  [NEW]     +48  [ = ]       0    BaroThrustEstimator::desc
  [NEW]     +64  [ = ]       0    BaroThrustEstimator::init()
  [NEW]     +48  [ = ]       0    BaroThrustEstimator::print_status()
  [NEW]     +64  [ = ]       0    BaroThrustEstimator::print_usage()
  [NEW]     +64  [ = ]       0    BaroThrustEstimator::publishStatus()
  [NEW]     +48  [ = ]       0    BaroThrustEstimator::saveParameters()
  [NEW]     +64  [ = ]       0    BaroThrustEstimator::task_spawn()
  [NEW]     +32  [ = ]       0    BaroThrustEstimator::updateParams()
  [NEW]     +48  [ = ]       0    BaroThrustEstimator::updateParamsImpl()
 -96.2%    +576  [ = ]       0    [34 Others]
 +13% +1.22Ki  [ = ]       0    [Unmapped]
+0.4%  +169Ki  +0.3% +6.78Ki    TOTAL

px4_fmu-v6x [Total VM Diff: 6756 byte (0.35 %)]
    FILE SIZE        VM SIZE    
--------------  -------------- 
+0.3% +6.59Ki  +0.3% +6.59Ki    .text
  [NEW] +1.33Ki  [NEW] +1.33Ki    BaroThrustEstimator::Run()
  +0.4%    +644  +0.4%    +644    [section .text]
 -99.3%    +568 -99.3%    +568    [83 Others]
  [NEW]    +516  [NEW]    +516    BaroThrustEstimator::BaroThrustEstimator()
  [NEW]    +376  [NEW]    +376    BaroThrustCfRls::checkConvergence()
  +0.2%    +372  +0.2%    +372    g_cromfs_image
  [NEW]    +340  [NEW]    +340    BaroThrustCfRls::RlsEstimator::update()
  [NEW]    +316  [NEW]    +316    BaroThrustEstimator::saveParameters()
  [NEW]    +296  [NEW]    +296    BaroThrustEstimator::~BaroThrustEstimator()
   +72%    +204   +72%    +204    EKF2::UpdateMagSample()
  [NEW]    +192  [NEW]    +192    sensors::VehicleAirData::thrustCompensation()
  [NEW]    +188  [NEW]    +188    BaroThrustCfRls::updateEstimator()
  [NEW]    +180  [NEW]    +180    BaroThrustEstimator::print_status()
  [NEW]    +172  [NEW]    +172    BaroThrustCfRls::updateCf()
   +65%    +164   +65%    +164    EKF2::UpdateBaroSample()
  [NEW]    +160  [NEW]    +160    BaroThrustCfRls::computeAccelUp()
  [NEW]    +156  [NEW]    +156    BaroThrustEstimator::publishStatus()
   +14%    +156   +14%    +156    param_modify_on_import()
  [NEW]    +136  [NEW]    +136    BaroThrustEstimator::task_spawn()
  [NEW]    +128  [NEW]    +128    BaroThrustEstimator::init()
  [NEW]    +124  [NEW]    +124    sensors::VehicleAirData::updateThrustBuffer()
+1.1%      +4  +1.1%      +4    .init_section
+0.3% +6.13Ki  [ = ]       0    .debug_abbrev
+0.2%    +400  [ = ]       0    .debug_aranges
+0.3% +1.36Ki  [ = ]       0    .debug_frame
+0.4%  +112Ki  [ = ]       0    .debug_info
+0.3% +17.5Ki  [ = ]       0    .debug_line
   +40%      +2  [ = ]       0    [Unmapped]
  +0.3% +17.5Ki  [ = ]       0    [section .debug_line]
+0.3% +12.1Ki  [ = ]       0    .debug_loclists
+0.4% +2.48Ki  [ = ]       0    .debug_rnglists
  [DEL]      -1  [ = ]       0    [Unmapped]
  +0.4% +2.48Ki  [ = ]       0    [section .debug_rnglists]
+0.2% +6.14Ki  [ = ]       0    .debug_str
+0.2% +1.32Ki  [ = ]       0    .strtab
  [NEW]     +43  [ = ]       0    BaroThrustCfRls::RlsEstimator::reset()
  [NEW]     +47  [ = ]       0    BaroThrustCfRls::RlsEstimator::update()
  [NEW]     +42  [ = ]       0    BaroThrustCfRls::checkConvergence()
  [NEW]     +82  [ = ]       0    BaroThrustCfRls::computeAccelUp()
  [NEW]     +29  [ = ]       0    BaroThrustCfRls::reset()
  [NEW]     +34  [ = ]       0    BaroThrustCfRls::updateCf()
  [NEW]     +42  [ = ]       0    BaroThrustCfRls::updateEstimator()
  [NEW]     +26  [ = ]       0    BaroThrustEstimator
  [NEW]     +58  [ = ]       0    BaroThrustEstimator::BaroThrustEstimator()
  [NEW]     +68  [ = ]       0    BaroThrustEstimator::Run()
  [NEW]     +46  [ = ]       0    BaroThrustEstimator::custom_command()
  [NEW]     +32  [ = ]       0    BaroThrustEstimator::init()
  [NEW]     +41  [ = ]       0    BaroThrustEstimator::print_status()
  [NEW]     +42  [ = ]       0    BaroThrustEstimator::print_usage()
  [NEW]     +44  [ = ]       0    BaroThrustEstimator::publishStatus()
  [NEW]     +43  [ = ]       0    BaroThrustEstimator::saveParameters()
  [NEW]     +42  [ = ]       0    BaroThrustEstimator::task_spawn()
  [NEW]     +87  [ = ]       0    BaroThrustEstimator::updateParams()
  [NEW]     +95  [ = ]       0    BaroThrustEstimator::updateParamsImpl()
  [NEW]    +225  [ = ]       0    BaroThrustEstimator::~BaroThrustEstimator()
 -99.4%    +188  [ = ]       0    [7 Others]
+0.3% +1.64Ki  [ = ]       0    .symtab
  [NEW]     +48  [ = ]       0    BaroThrustCfRls::RlsEstimator::reset()
  [NEW]     +48  [ = ]       0    BaroThrustCfRls::RlsEstimator::update()
  [NEW]     +48  [ = ]       0    BaroThrustCfRls::checkConvergence()
  [NEW]     +64  [ = ]       0    BaroThrustCfRls::computeAccelUp()
  [NEW]     +48  [ = ]       0    BaroThrustCfRls::reset()
  [NEW]     +48  [ = ]       0    BaroThrustCfRls::updateCf()
  [NEW]     +48  [ = ]       0    BaroThrustCfRls::updateEstimator()
  [NEW]     +32  [ = ]       0    BaroThrustEstimator
  [NEW]     +64  [ = ]       0    BaroThrustEstimator::BaroThrustEstimator()
  [NEW]    +112  [ = ]       0    BaroThrustEstimator::Run()
  [NEW]     +64  [ = ]       0    BaroThrustEstimator::custom_command()
  [NEW]     +48  [ = ]       0    BaroThrustEstimator::desc
  [NEW]     +64  [ = ]       0    BaroThrustEstimator::init()
  [NEW]     +48  [ = ]       0    BaroThrustEstimator::print_status()
  [NEW]     +64  [ = ]       0    BaroThrustEstimator::print_usage()
  [NEW]     +64  [ = ]       0    BaroThrustEstimator::publishStatus()
  [NEW]     +48  [ = ]       0    BaroThrustEstimator::saveParameters()
  [NEW]     +64  [ = ]       0    BaroThrustEstimator::task_spawn()
  [NEW]     +32  [ = ]       0    BaroThrustEstimator::updateParams()
  [NEW]     +48  [ = ]       0    BaroThrustEstimator::updateParamsImpl()
 -83.4%    +576  [ = ]       0    [26 Others]
 +29% +1.40Ki  [ = ]       0    [Unmapped]
+0.4%  +169Ki  +0.3% +6.60Ki    TOTAL

Updated: 2026-04-02T05:53:55

@dakejahl dakejahl force-pushed the dakejahl/baro-thrust-estimator-pr branch from ffb1050 to 98027e9 Compare April 1, 2026 01:14
@DronecodeBot
Copy link
Copy Markdown

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

@dakejahl dakejahl force-pushed the dakejahl/baro-thrust-estimator-pr branch 3 times, most recently from 23072a3 to 7c460fc Compare April 1, 2026 02:07
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.
@dakejahl dakejahl force-pushed the dakejahl/baro-thrust-estimator-pr branch from 7c460fc to c4596df Compare April 1, 2026 02:39
@dakejahl dakejahl force-pushed the dakejahl/baro-thrust-estimator-pr branch 2 times, most recently from b66880d to f2f31bf Compare April 1, 2026 06:39
@github-actions
Copy link
Copy Markdown

github-actions Bot commented Apr 1, 2026

No broken links found in changed files.

@dakejahl dakejahl force-pushed the dakejahl/baro-thrust-estimator-pr branch from f2f31bf to ebfd5b9 Compare April 1, 2026 06:51
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.
@dakejahl dakejahl force-pushed the dakejahl/baro-thrust-estimator-pr branch from ec05049 to c75c9cb Compare April 1, 2026 07:43
dakejahl added 2 commits April 1, 2026 00:02
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.
@bresch
Copy link
Copy Markdown
Member

bresch commented Apr 1, 2026

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?
Should the user just perform throttle punches during the initial flight? Since flying forwards at constant altitude requires more thrust than while hovering, this will also be coupled in the estimate; did you test that?

@bresch
Copy link
Copy Markdown
Member

bresch commented Apr 1, 2026

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").

Comment on lines +1 to +11
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)
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

Needs a short descriptiona and a long description. Below just fixes up the units. I am assuming that the variance has no units.

Suggested change
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
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

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

@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.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Projects

None yet

Development

Successfully merging this pull request may close these issues.

4 participants