Skip to content

refactor(sensors): move baro/mag rate limiting from publishers to EKF2#26921

Open
dakejahl wants to merge 2 commits intoPX4:mainfrom
dakejahl:dakejahl/baro-mag-rate-limiting
Open

refactor(sensors): move baro/mag rate limiting from publishers to EKF2#26921
dakejahl wants to merge 2 commits intoPX4:mainfrom
dakejahl:dakejahl/baro-mag-rate-limiting

Conversation

@dakejahl
Copy link
Copy Markdown
Contributor

@dakejahl dakejahl commented Mar 31, 2026

Summary

Move barometer and magnetometer rate limiting from the sensor publisher modules (VehicleAirData, VehicleMagnetometer) to the EKF2 consumer module. Sensors now publish at full sensor rate; rate gating happens at fusion time.

Background

Rate limiting was originally added on the publisher side to reduce estimator and logging overhead:

These were reasonable optimizations at the time. However, the publish-side implementation has two issues:

1. Aliasing. When the sensor rate is close to the configured limit (e.g. 23 Hz BMP390 baro with SENS_BARO_RATE = 20 Hz), the rate limiter creates irregular publication intervals — sometimes accumulating 2 samples, sometimes 1 — depending on phase alignment between the sensor and the rate check.

2. Box car filtering. The accumulate-and-average behavior applies a rectangular (box car) window to the sensor data before publishing. This introduces group delay proportional to the number of accumulated samples, and the sinc-shaped frequency response has poor stopband attenuation. Moving rate gating to the EKF consumer eliminates this — the EKF receives the actual sensor value at the selected sample time, not a windowed average.

Changes

  • Remove SENS_BARO_RATE / SENS_MAG_RATE from sensor publishers — sensors now publish every sample at full sensor rate
  • Add EKF2_BARO_RATE (default 20 Hz) / EKF2_MAG_RATE (default 15 Hz) in EKF2 to gate setBaroData() / setMagData() calls
  • Parameter migration translates SENS_BARO_RATE -> EKF2_BARO_RATE and SENS_MAG_RATE -> EKF2_MAG_RATE on import
  • Full-rate data now available to logger and other consumers

EKF fusion rates are unchanged at default settings (20 Hz baro, 15 Hz mag).

File Change
VehicleAirData.cpp/.hpp Remove SENS_BARO_RATE rate-limit loop, publish every sample
VehicleMagnetometer.cpp/.hpp Remove SENS_MAG_RATE rate-limit loop, publish every sample
params.yaml / sensor_params_mag.yaml Remove SENS_BARO_RATE / SENS_MAG_RATE definitions
EKF2.cpp/.hpp Add rate gating in UpdateBaroSample() / UpdateMagSample()
params_barometer.yaml / params_magnetometer.yaml Add EKF2_BARO_RATE / EKF2_MAG_RATE
param_translation.cpp Migrate old params on import

Test plan

  • Before/after flight logs comparing EKF baro/mag innovation statistics
  • Verify baro/mag publish interval regularity (aliasing fix)
  • Measure CPU load delta from increased publish rate
  • Confirm parameter migration works on existing param files

@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/1

@dakejahl dakejahl force-pushed the dakejahl/baro-mag-rate-limiting branch from 5ff081a to 0d0e9ca Compare April 1, 2026 01:14
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-mag-rate-limiting branch from 0d0e9ca to dc4cf03 Compare April 1, 2026 02:08
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.
@dakejahl
Copy link
Copy Markdown
Contributor Author

dakejahl commented Apr 1, 2026

Pushed a follow-up commit that adds prefiltering before the rate-limited setBaroData()/setMagData() calls.

The initial implementation was pure decimation — pick one sample per fusion interval, drop the rest. This works fine when the sensor rate is close to the fusion rate (e.g. BMP390 at 23 Hz → 20 Hz fusion), but for higher-rate sensors (MS5611 at 100+ Hz → 20 Hz fusion) it throws away ~4 out of 5 samples and loses the sqrt(N) noise reduction that the old publish-side averaging provided.

The fix accumulates all incoming samples between fusion intervals and pushes the average to the EKF. This is effectively the same box car filter as before, but without the aliasing problem — because EKF2 runs at IMU rate and sees every published sample, the accumulation count is consistently sensor_rate / fusion_rate rather than jittering between 1 and 2 due to phase alignment between the sensor clock and the rate-limiter check.

@dakejahl dakejahl requested a review from dagar April 1, 2026 07:25
@bresch
Copy link
Copy Markdown
Member

bresch commented Apr 1, 2026

Why don't we rate limit directly in the driver that by definition sees the data at full rate? We don't need to consume the baro or mag data at full rate anywhere.

@dakejahl
Copy link
Copy Markdown
Contributor Author

dakejahl commented Apr 1, 2026

Why don't we rate limit directly in the driver that by definition sees the data at full rate? We don't need to consume the baro or mag data at full rate anywhere.

Sure, in that case this PR would be much smaller and simply fix the aliasing bug. I implemented it this way because it allows the logger and any future consumers (baro_thrust_estimator + compensation) to see the full-rate. But in practice the baro_thrust_estimator + compensation doesn't need the full-rate and may actually benefit from using the filtered values. The full-rate visibility at the logger could be useful for debugging and log analysis. IMO architecturally it makes more sense to publish full-rate data and let consumers decide how to process it.

I am not strongly opinionated on this though. If you'd like I can close this PR in favor of a new PR that simply fixes the aliasing bug. In the future we could go this route once there is clear justification.

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

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

3 participants