Skip to content

Commit f2f31bf

Browse files
committed
feat(docs): baro throttle compensation
1 parent 41bfe6c commit f2f31bf

3 files changed

Lines changed: 118 additions & 0 deletions

File tree

docs/en/SUMMARY.md

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -228,6 +228,7 @@
228228
- [Airspeed Validation](advanced_config/airspeed_validation.md)
229229
- [TFSlot Airspeed Sensor](sensor/airspeed_tfslot.md)
230230
- [Barometers](sensor/barometer.md)
231+
- [Thrust Compensation](advanced_config/barometer_thrust_compensation.md)
231232
- [Distance Sensors \(Rangefinders\)](sensor/rangefinders.md)
232233
- [Ainstein US-D1 Standard Radar Altimeter](sensor/ulanding_radar.md)
233234
- [ARK DIST SR (CAN/UART)](dronecan/ark_dist.md)
Lines changed: 116 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,116 @@
1+
# Barometer Thrust Compensation
2+
3+
Propellers change the static pressure at the barometer sensor proportional to motor output.
4+
This creates a thrust-dependent altitude error that can reach several metres on small vehicles with the barometer close to the propellers.
5+
The direction and magnitude depend on sensor placement relative to the propellers.
6+
7+
PX4 can compensate for this error by applying a correction proportional to the vertical thrust setpoint:
8+
9+
```
10+
corrected_baro_alt = raw_baro_alt + SENS_BARO_PCOEF * |thrust_z|
11+
```
12+
13+
where `thrust_z` is the Z body-axis component of `vehicle_thrust_setpoint` (negative for upward thrust in FRD frame).
14+
15+
The compensation parameter [SENS_BARO_PCOEF](../advanced_config/parameter_reference.md#SENS_BARO_PCOEF) can be identified automatically during flight or manually from a flight log.
16+
17+
::: info
18+
This feature compensates for _propwash-induced_ pressure error, which depends on motor output.
19+
For _airspeed-induced_ static pressure error (due to vehicle forward motion), see [Static Pressure Buildup](../advanced_config/static_pressure_buildup.md).
20+
:::
21+
22+
## Online Calibration (Recommended)
23+
24+
The online estimator identifies `SENS_BARO_PCOEF` automatically during flight and saves the result on disarm.
25+
26+
### How It Works
27+
28+
A complementary filter (CF) fuses barometer altitude with double-integrated accelerometer data at a very low crossover frequency (default 0.1 Hz).
29+
The CF trusts the accelerometer for fast altitude changes and the barometer for slow drift, so the CF residual (baro minus accel prediction) isolates thrust-correlated pressure error while rejecting real altitude changes.
30+
31+
A Recursive Least Squares (RLS) estimator then fits the linear model `residual = K * thrust + bias` to identify the gain K.
32+
Once the estimate converges (stable K, low variance, sufficient thrust excitation), K is locked and saved to `SENS_BARO_PCOEF` on disarm.
33+
34+
The estimator refines the parameter over subsequent flights — each flight corrects for whatever residual error remains after the previous calibration.
35+
36+
### Setup
37+
38+
1. Set [SENS_BAR_AUTOCAL](../advanced_config/parameter_reference.md#SENS_BAR_AUTOCAL) to **3** (enables both GNSS altitude calibration and thrust compensation).
39+
2. Fly normally for at least 60 seconds with some altitude variation.
40+
3. On disarm, the estimated `SENS_BARO_PCOEF` is saved automatically if the estimator converged.
41+
4. Check convergence after flight:
42+
- In the console: `baro_thrust_estimator status`
43+
- In a log: look at the `baro_thrust_estimate` topic — `converged` should be true.
44+
45+
The estimator uses several convergence gates before saving:
46+
47+
| Gate | Threshold | Purpose |
48+
|------|-----------|---------|
49+
| Minimum flight time | 30 s | Allow RLS to settle |
50+
| K variance (P[0][0]) | < 3.0 | Parameter estimate is precise |
51+
| Prediction error | Low absolute or relative | Model fits the data |
52+
| Thrust excitation | std > 0.05 | Enough signal to identify K |
53+
| K stability | Stable for 10 s | Estimate is not drifting |
54+
| Hold time | 10 s | Convergence is sustained |
55+
56+
::: tip
57+
Altitude changes during hover provide the thrust excitation the estimator needs.
58+
Constant-thrust hover with no altitude variation will not converge.
59+
:::
60+
61+
### Parameters
62+
63+
| Parameter | Default | Description |
64+
|-----------|---------|-------------|
65+
| [SENS_BARO_PCOEF](../advanced_config/parameter_reference.md#SENS_BARO_PCOEF) | 0.0 | Baro altitude correction per unit vertical thrust \[m\]. Identified by the estimator or set manually. |
66+
| [SENS_BAR_AUTOCAL](../advanced_config/parameter_reference.md#SENS_BAR_AUTOCAL) | 1 | Bitmask: bit 0 = GNSS altitude offset, bit 1 = online thrust compensation. Set to 3 for both. |
67+
| [SENS_BAR_CF_BW](../advanced_config/parameter_reference.md#SENS_BAR_CF_BW) | 0.1 | CF crossover frequency \[Hz\]. Lower = more conservative, higher = faster identification but noisier. |
68+
69+
### Soft Guards
70+
71+
The estimator pauses RLS updates (while keeping the CF running) when:
72+
73+
- Vertical speed exceeds 2 m/s
74+
- Horizontal speed exceeds 5 m/s
75+
76+
This prevents high-speed flight dynamics from corrupting the estimate.
77+
Once converged, the RLS is frozen entirely to prevent ground-effect contamination during landing.
78+
79+
## Manual Calibration
80+
81+
If you prefer not to use the online estimator, you can identify `SENS_BARO_PCOEF` from a flight log using a range sensor as ground truth.
82+
83+
1. Set `SENS_BARO_PCOEF` to 0 (disable existing compensation).
84+
2. Fly a hover at 2-5 m AGL for at least 60 seconds with gentle altitude changes. A downward-facing range sensor must be installed.
85+
3. Run the analysis script on the log:
86+
```sh
87+
python3 Tools/baro_compensation/baro_thrust_calibration.py <path/to/log.ulg>
88+
```
89+
4. Apply the recommended `SENS_BARO_PCOEF` value.
90+
5. Fly again and re-run the script to verify the compensation.
91+
92+
The script automatically selects an analysis mode based on available data:
93+
94+
| Mode | Data Required | Output |
95+
|------|--------------|--------|
96+
| Estimator review | Online estimator logged | K convergence, residual analysis |
97+
| Full validation | Estimator + range sensor | Cross-validation of online vs offline K |
98+
| Standalone calibration | Range sensor only | Recommended PCOEF from least-squares fit |
99+
100+
## Interpreting Results
101+
102+
| Metric | Good | Marginal | Poor |
103+
|--------|------|----------|------|
104+
| Thrust correlation \|r\| | > 0.6 | 0.3 - 0.6 | < 0.3 |
105+
| Model R^2 | > 0.3 | 0.1 - 0.3 | < 0.1 |
106+
| Compensated \|r\| | < 0.2 | 0.2 - 0.4 | > 0.4 |
107+
108+
- **Low R^2**: Thrust is not the dominant baro error source. Check for thermal drift, ground effect, or sensor placement issues.
109+
- **Online/offline K disagreement > 2 m**: The estimator may need more excitation. Fly longer or with more altitude variation.
110+
111+
## See Also
112+
113+
- [Static Pressure Buildup](../advanced_config/static_pressure_buildup.md) — airspeed-induced barometer error
114+
- [Compass Power Compensation](../advanced_config/compass_power_compensation.md) — analogous compensation for magnetometer
115+
- [Sensor Thermal Compensation](../advanced_config/sensor_thermal_calibration.md) — temperature-induced sensor error
116+
- [Using PX4's Navigation Filter (EKF2)](../advanced_config/tuning_the_ecl_ekf.md) — EKF2 height fusion configuration

docs/en/advanced_config/index.md

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@ This topic lists configuration topics that are not particularly vehicle specific
2222
- [Compass Power Compensation](../advanced_config/compass_power_compensation.md)
2323
- [Advanced Controller Orientation](../advanced_config/advanced_flight_controller_orientation_leveling.md)
2424
- [Static Pressure Buildup](../advanced_config/static_pressure_buildup.md)
25+
- [Barometer Thrust Compensation](../advanced_config/barometer_thrust_compensation.md)
2526

2627
## Serial port/Ethernet configuration
2728

0 commit comments

Comments
 (0)