MAVLINKHUD

Overview

The BARO parameter group configures the Barometric Pressure Sensors (Barometers). These sensors measure atmospheric pressure to estimate the vehicle's Altitude relative to the launch point (AGL).

Barometers are the primary altitude source for most flight modes (AltHold, Loiter, Auto). They are sensitive to:

  1. Light: Sunlight striking the sensor element can cause jumps (cover with open-cell foam).
  2. Wind/Prop Wash: Airflow over the sensor creates pressure variations (Bernoulli effect), leading to altitude errors.
  3. Temperature: Drift occurs as the board heats up.

Key Concepts

1. Primary Sensor (BARO_PRIMARY)

ArduPilot supports up to 3 redundant barometers. This parameter selects which one is trusted by the EKF (State Estimator) by default.

  • 0: First detected (Internal).
  • 1: Second detected.
  • 2: Third detected.

2. Ground Reference (BARO_GND_TEMP)

The barometer calculates altitude based on the temperature and pressure measured on the ground during arming.

  • BARO_FIELD_ELV: Allows manually setting the takeoff elevation (AMSL) if known, to improve absolute altitude reporting.

3. Wind Compensation (BARO1_WCF_...)

These parameters provide Wind Coefficient corrections. If your drone's altitude reading changes significantly when flying forward vs. hovering (due to dynamic pressure build-up inside the fuselage), you can tune these coefficients to subtract the speed-induced pressure error.

Parameter Breakdown

  • BARO_ENABLE: Master switch.
  • BARO_PRIMARY: Active sensor selector.
  • BARO_ALT_OFFSET: Calibration offset (tuning).
  • BARO_ALTERR_MAX: Maximum allowed difference between GPS and Baro altitude before pre-arm failure.
  • BARO_PROBE_EXT: Probe for external I2C barometers (BMP280, DPS310, etc.).

Integration Guide

Hardware Setup

  • Foam: ALWAYS cover the barometer chip on the flight controller with open-cell foam and a breathable case to shield it from light and direct airflow.
  • External: If the internal baro is noisy or subject to heat, use an external DroneCAN or I2C barometer mounted in a better location.

Troubleshooting "Baro Drift"

  • If altitude rises while the drone is sitting on the bench: Thermal Drift. Wait for the board to warm up before flying.
  • If altitude drops when you throttle up: Prop Wash. Improve isolation/foam.
  • If altitude changes when flying fast: Dynamic Pressure. Tune WCF params or move the static port.

Developer Notes

  • Library: libraries/AP_Baro
  • Singleton: AP_Baro::get_singleton()
  • Drivers: Supports MS5611, BMP280, DPS310, ICP10100, and many others.

BARO1_DEVID

Default 0

Barometer 1 Device ID (BARO1_DEVID)

Description

BARO1_DEVID is a Read-Only parameter that identifies the specific barometer hardware detected by the autopilot as the primary sensor. It includes information about the sensor type (e.g., BMP280, MS5611), the communication bus (I2C/SPI), and the bus address.

  • Role: Diagnostic tool to verify that the expected barometer is being used.
  • Usage: If this is 0, the autopilot has failed to detect any barometer on the expected pins/buses.

The Engineer's View

The ID is encoded using the standard ArduPilot DeviceID structure.
It is populated during the AP_Baro::init() sequence when the driver successfully probes the hardware.

Tuning & Behavior

  • Default: 0 (Detection failed or not yet performed).
  • Action: If your drone has multiple barometers, you can use this ID to identify which one is which in the logs.

BARO1_GND_PRESS

Pa
Default 0
Range 0 110000

Ground Pressure (BARO1_GND_PRESS)

Description

BARO1_GND_PRESS stores the atmospheric pressure measured when the drone was last "Zeroed" (usually at arming or during the initial power-up).

The autopilot uses this as the reference (Sea Level equivalent) to calculate relative altitude.

  • Units: Pascals (Pa).
  • Standard Pressure: Approximately 101325 Pa.

The Engineer's View

Stored in AP_Baro::sensors[0].ground_pressure.
It is updated during the ground calibration phase. The EKF uses this value to initialize the altitude state.

Tuning & Behavior

  • Default: 0 (Updated automatically).
  • Maintenance: You should not need to edit this manually. If your drone reports a large altitude offset immediately after arming, ensure the barometer is not covered by foam or exposed to direct sunlight/wind.

BARO1_WCF_BCK

Default 0
Range -1.0 1.0

Baro Wind Compensation Backward (BARO1_WCF_BCK)

Description

BARO1_WCF_BCK compensates for pressure errors during backward flight. See BARO1_WCF_FWD for more details.

BARO1_WCF_DN

Default 0
Range -1.0 1.0

Baro Wind Compensation Down (BARO1_WCF_DN)

Description

BARO1_WCF_DN compensates for pressure errors during downward (vertical) flight. See BARO1_WCF_FWD for more details.

BARO1_WCF_FWD

Default 0
Range -1.0 1.0

Baro Wind Compensation Forward (BARO1_WCF_FWD)

Description

BARO1_WCF_FWD compensates for the "Pressure Hull" effect.

When a drone flies forward at high speed, air can pile up or create a vacuum around the barometer sensor (depending on the fuselage shape and venting). This creates a false pressure reading, making the drone think it is climbing or diving when it is actually level. This coefficient allows the EKF to use airspeed/acceleration data to cancel out this error.

  • Positive Value: Corrects for high pressure (compression).
  • Negative Value: Corrects for low pressure (suction).

Tuning & Behavior

  • Default: 0.
  • Tuning: Fly at high speed in a straight line. If the drone loses altitude as it speeds up (thinking it is higher than it is), adjust this coefficient until the altitude remains steady.
  • Dependencies: Requires a functional EKF3 and correctly configured drag coefficients.

BARO1_WCF_LFT

Default 0
Range -1.0 1.0

Baro Wind Compensation Left (BARO1_WCF_LFT)

Description

BARO1_WCF_LFT compensates for pressure errors during leftward (sideways) flight. See BARO1_WCF_FWD for more details.

BARO1_WCF_RGT

Default 0
Range -1.0 1.0

Baro Wind Compensation Right (BARO1_WCF_RGT)

Description

BARO1_WCF_RGT compensates for pressure errors during rightward (sideways) flight. See BARO1_WCF_FWD for more details.

BARO1_WCF_UP

Default 0
Range -1.0 1.0

Baro Wind Compensation Up (BARO1_WCF_UP)

Description

BARO1_WCF_UP compensates for pressure errors during upward (vertical) flight. See BARO1_WCF_FWD for more details.

BARO2_DEVID

Default 0
Range null

Baro ID2

Note: This parameter functions identically to BARO1_DEVID.

BARO2_GND_PRESS

Pa
Default 0
Range null

Ground Pressure

Note: This parameter functions identically to BARO1_GND_PRESS.

BARO3_DEVID

Default 0
Range null

Baro ID3

Note: This parameter functions identically to BARO1_DEVID.

BARO3_GND_PRESS

Pa
Default 0
Range null

Absolute Pressure

Note: This parameter functions identically to BARO1_GND_PRESS.

BARO_ALTERR_MAX

m
Default 2000
Range 0 5000

Altitude error maximum (BARO_ALTERR_MAX)

Description

This parameter is a pre-arm safety check that compares the altitude reported by the GPS to the altitude calculated from the barometer. It is designed to catch "Hardware Substitutions" or faulty sensors before you take off.

A common issue in the hardware market is vendors substituting one barometer model (like the MS5607) for another (like the MS5611) without updating the firmware settings. This causes the altitude to be calculated incorrectly (often off by thousands of meters). This check prevents the vehicle from arming if such a massive discrepancy is detected.

The Mathematics

The autopilot compares the GPS altitude ($Alt\_{AMSL}$) to the barometric pressure altitude calculated against the Standard Sea Level (SSL) atmosphere.

$$ Error = |Alt\_{GPS} - Alt\_{Baro\_SSL}| $$

If $Error > BARO\_ALTERR\_MAX$, the arming check fails.

The Engineer's View

In AP_Baro::arming_checks() (libraries/AP_Baro/AP_Baro.cpp):

  1. The code verifies a valid 3D GPS fix is available.
  2. It calculates alt_pressure = get_altitude_difference(SSL_AIR_PRESSURE, get_pressure()).
  3. It compares this to gps.location().alt.
  4. If the gap is too large, it returns the error message: "GPS alt error [X]m (see BARO_ALTERR_MAX)".

Tuning & Behavior

  • Default Value: 2000 meters.
  • Usage: You should not typically need to tune this. If you are getting this error, it is a strong signal that your barometer is either faulty or misconfigured.
  • 0: Disables this safety check.
  • Hardware Fix: If you are certain your hardware is an MS5607 being treated as an MS5611, refer to the BARO_OPTIONS parameter to force the correct driver behavior.

BARO_ALT_OFFSET

m
Default 0
Range null

Altitude offset (BARO_ALT_OFFSET)

Description

This parameter allows for a manual bias (offset) to be added to the calculated barometric altitude. It is primarily used by Ground Control Stations (GCS) to synchronize the aircraft's altitude with a known ground reference point or a GCS-integrated barometer.

It essentially "shifts" the entire altitude profile up or down by the specified number of meters.

The Mathematics

The offset is added directly to the final altitude calculation for every sensor instance.

$$ Alt\_{reported} = Alt\_{raw} + BARO\_ALT\_OFFSET $$

To prevent "jerking" the flight controllers (which could upset the EKF), ArduPilot slews this value slowly over time rather than applying it as a step function.

The Engineer's View

In AP_Baro::update(), the code checks if _alt_offset has changed:
_alt_offset_active = (0.98f*_alt_offset_active) + (0.02f*_alt_offset);
This implementation acts as a low-pass filter (98% old, 2% new) to smoothly transition to a new offset.
The value is reset to 0 every time a full barometer calibration is performed (e.g., on reboot).

Tuning & Behavior

  • Default Value: 0 meters.
  • Usage: Typically modified via MAVLink by a GCS rather than tuned manually by a user.
  • Persistence: This value is saved to EEPROM but is automatically reset to 0 during the AP_Baro::calibrate() call on boot.

BARO_ENABLE

Option
Default 1
Range 0 1

Barometer Enable (BARO_ENABLE)

Description

This parameter is the master switch for the barometer driver. It is primarily used on CAN-based peripheral nodes (AP_Periph) to enable or disable the onboard pressure sensor.

If your peripheral node has a physical barometer installed, setting this to 1 allows the node to start measuring pressure and reporting it to the main flight controller over the CAN bus.

The Mathematics

This is a binary switch:

  • 0: Disabled (Driver not initialized)
  • 1: Enabled (Driver initialized and reporting)

The Engineer's View

In AP_Periph code, this parameter maps to g.baro_enable. It is used during the boot sequence to decide whether to call baro.init(). If disabled, no memory is allocated for barometer drivers, and no DroneCAN barometer messages are transmitted.

Tuning & Behavior

  • Default Value: 1 (Enabled).
  • Usage: Only set to 0 if your hardware lacks a barometer or if you are using the node for a different purpose (like a dedicated GPS) and want to reduce CAN bus traffic.
  • Reboot Required: Yes. Driver initialization happens only at startup.

BARO_EXP

Exponent
Default 0
Range null

Baro Temperature Correction Exponent (BARO_EXP)

Description

This parameter is part of ArduPilot's advanced temperature calibration system. Many barometric sensors exhibit a "drift" where the reported pressure changes simply because the sensor is heating up, even if the altitude remains constant. This is a common issue with sensors like the ICM-20789.

BARO_EXP stores a learned mathematical exponent that models this drift. When temperature calibration is enabled, the autopilot uses this value to "cancel out" the temperature-induced pressure changes, resulting in a much more stable altitude estimate during long flights or in varying weather conditions.

The Mathematics

The correction applied to the raw pressure ($P\_{raw}$) is a power function based on the temperature difference from a reference point ($T\_{zero}$, typically 20°C):

$$ P\_{corrected} = P\_{raw} + \text{max}(T - T\_{zero}, 0)^{BARO\_EXP} $$

This model is chosen for its robustness and its ability to accurately fit the physical characteristics of high-drift barometers.

The Engineer's View

In AP_TempCalibration.cpp, this parameter is defined as _BARO_EXP (internal name baro_exponent).

  • Learning Phase: When TCAL_ENABLED is set to 2 (EnableAndLearn), the system monitors pressure vs. temperature while the vehicle is sitting still on the ground. It uses a least-squares error minimization approach to find the exponent that best flattens the pressure curve.
  • Application: Once learned, the exponent is saved to this parameter. In subsequent flights (with TCAL_ENABLED=1), AP_TempCalibration::apply_calibration() uses this exponent to provide a real-time p_correction to the AP_Baro library.

Tuning & Behavior

  • Default Value: 0 (No correction).
  • How to Set: Do not set this manually. Instead, set TCAL_ENABLED=2, power on your vehicle, and let it sit still while the internal electronics warm up (about 10-15 minutes). The system will automatically calculate and save the optimal BARO_EXP.
  • Range: Typically between 0.0 and 2.0.
  • Effect: A successful calibration will result in the "Baro Altitude" remaining near 0.0m even as the flight controller gets hot.

BARO_EXT_BUS

Default -1
Range -1 6

External Barometer I2C Bus (BARO_EXT_BUS)

Description

BARO_EXT_BUS is used if you are connecting an external high-precision barometer to your flight controller via an I2C cable.

  • -1 (Disabled/Auto): The flight controller will probe all external buses automatically.
  • 0-6: Forces the flight controller to look on a specific I2C bus for the sensor.

The Engineer's View

Used in AP_Baro::init().
Manually setting the bus can speed up the boot process and prevent conflicts if multiple devices on different buses have the same I2C address.

Tuning & Behavior

  • Default Value: -1
  • Recommendation: Leave at -1 unless you have a specific hardware conflict or are using an unusual board configuration.

BARO_FIELD_ELV

m
Default 0

Field elevation (BARO_FIELD_ELV)

Description

This parameter allows the user to manually enter the known elevation of the takeoff location (field elevation) in meters above mean sea level (AMSL). This provides a known reference altitude for the EKF and barometer before a GPS fix is obtained, ensuring more accurate absolute altitude reporting from startup.

The Mathematics

$$ \text{Altitude}{\text{AMSL}} \approx \text{Altitude}{\text{Baro}} + \text{BARO\_FIELD\_ELV} $$

If BARO_FIELD_ELV is 0, the system attempts to initialize the origin altitude from GPS or other sources once available.

The Engineer's View

Defined in libraries/AP_Baro/AP_Baro.cpp. The parameter _field_elevation is used to set _field_elevation_active. It is non-persistent across reboots in typical usage (resets to 0) to prevent taking off from a different location with an incorrect fixed elevation, though the parameter definition itself allows storage. The code logic often resets it or prioritizes GPS data once valid.

Tuning & Behavior

  • Default Value: 0 m
  • Set to: Known altitude of the launch site (e.g., 100m).
  • Note: This is primarily for advanced users or operations in GPS-denied environments where absolute altitude reference is required from power-on.

BARO_FLTR_RNG

%
Default 0
Range 0 100

Filter Range (BARO_FLTR_RNG)

Description

This parameter acts as a "Noise Gate" for barometric pressure samples. It defines a percentage-based threshold around the current moving average. Any new pressure reading that falls outside of this window is rejected as "glitchy" noise and ignored.

This is extremely useful for protecting the altitude estimate from electromagnetic interference (EMI) or voltage spikes on the I2C bus, which can cause sudden, unrealistic jumps in pressure readings.

The Mathematics

A sample ($P\_{new}$) is only accepted if it is within $\pm X\%$ of the current smoothed average ($P\_{avg}$):

$$ |P\_{new} - P\_{avg}| \le P\_{avg} \times \frac{BARO\_FLTR\_RNG}{100} $$

If the new sample is outside this range, the system discards it and waits for the next sample.

The Engineer's View

In AP_Baro.cpp, this parameter maps to _filter_range.
It is primarily used in sensor backends (like AP_Baro_MS56XX.cpp or AP_Baro_BMP280.cpp) to validate raw pressure data before it enters the altitude conversion logic.

  • 0 (Default): Disables the check. All samples are accepted.
  • Setting it too tight: Can cause the barometer to "freeze" during rapid climbs or descents because the actual pressure change is faster than the allowed window.

Tuning & Behavior

  • Default Value: 0 (Filter disabled).
  • Recommended Value: If you experience altitude "glitches" or sudden jumps, try a value of 10 (10% window).
  • Symptom of too Low: Barometric altitude stops updating during high-performance maneuvers.
  • Symptom of too High: The sensor remains sensitive to electrical noise spikes.

BARO_GND_TEMP

degC
Default 0
Range -50 60

Ground Temperature (BARO_GND_TEMP)

Description

BARO_GND_TEMP allows you to manually specify the temperature at the takeoff location.

ArduPilot uses an "International Standard Atmosphere" (ISA) model to translate pressure changes into altitude. However, air density changes with temperature. If it is very hot or very cold, the standard model will have a significant error (the drone might think it is at 100m when it's really at 110m). Providing the actual ground temperature improves this calculation.

  • 0 (Default): The autopilot uses the temperature measured by its own internal sensor.
  • Non-Zero: Overrides the internal sensor with your manual reading.

Tuning & Behavior

  • Default: 0.
  • Usage: For most pilots, leave at 0. Only change this if you are performing precision survey work or high-altitude balloon flights where temperature gradients are critical.
  • Note: This parameter is reset to 0 upon reboot.

BARO_OPTIONS

Bitmask
Default 0
Range null

Barometer options (BARO_OPTIONS)

Description

This parameter is a bitmask used to enable specialized workarounds or features for barometric sensors.

Its primary current use is to solve a common "Hardware Identity Crisis": some manufacturers sell flight controllers labeled as containing an MS5611 barometer, but actually install an MS5607 (which is cheaper and looks identical). If the software treats an MS5607 as an MS5611, your altitude will be wildly incorrect. Enabling the workaround bit here forces the software to use the correct math for the substituted part.

The Mathematics

This parameter is a bitmask ($B$):

  • Bit 0 (Value 1): Treat MS5611 as MS5607.

If Bit 0 is set, the AP_Baro_MS56XX driver swaps the internal PROM coefficients and scaling constants ($C\_1$ to $C\_6$) to match the MS5607 physics model, ensuring correct pressure-to-altitude conversion.

The Engineer's View

In AP_Baro.cpp, this is defined as _options.
In AP_Baro_MS56XX::probe(), the driver checks the global AP_Baro options. If the "Treat as MS5607" bit is set, it overrides the auto-detected sensor type. This is necessary because the MS5611 and MS5607 have the same I2C/SPI identifiers and cannot always be distinguished purely by electronic signatures.

Tuning & Behavior

  • Bit 0 (Value 1): Enable the MS5611 $\rightarrow$ MS5607 workaround.
  • Usage: Only enable this if you are getting a BARO_ALTERR_MAX (GPS altitude discrepancy) error on a new flight controller and you suspect the manufacturer substituted the barometer.
  • Reboot Required: Yes. Barometer driver initialization happens on boot.

BARO_PRIMARY

Option
Default 0
Range 0 2

Primary barometer (BARO_PRIMARY)

Description

This parameter selects the "Master" barometer instance to be used for altitude estimation. Many modern flight controllers have multiple barometers (one internal and one or more external via CAN or I2C) for redundancy.

The primary barometer is the one whose data is prioritized by the EKF (Extended Kalman Filter) and reported to the pilot as the official barometric altitude.

The Mathematics

This is a simple index selection ($i$):

  • 0: 1st Baro (Instance 0)
  • 1: 2nd Baro (Instance 1)
  • 2: 3rd Baro (Instance 2)

The Engineer's View

In AP_Baro::update(), the logic selects the index stored in _primary_baro.
If the selected barometer becomes unhealthy during flight, ArduPilot has a failover mechanism that will automatically switch to the first healthy sensor it finds. However, BARO_PRIMARY defines the starting preference.

Tuning & Behavior

  • Default Value: 0.
  • Recommendation: If you have an external, high-precision barometer (e.g., inside a GPS module mounted away from wind/prop wash), set this to that instance number (often 1).
  • Detection: You can check which barometer is which by looking at the HWID or ID logs, or by blowing on the sensors and watching the BARO[x] altitude response in your Ground Control Station's status tab.

BARO_PROBE_EXT

Default 0
Range 0 16383

External Barometers to Probe (BARO_PROBE_EXT)

Description

BARO_PROBE_EXT tells ArduPilot which specific barometer hardware to look for on the external I2C bus.

By default, the autopilot attempts to detect the most common sensors automatically. However, if you are using an unusual or newer sensor that isn't being found, you may need to enable its bit in this parameter.

  • Bit 0: BMP085
  • Bit 1: BMP280
  • Bit 2: MS5611
  • Bit 3: MS5607
  • Bit 10: BMP388
  • Bit 11: SPL06

Tuning & Behavior

  • Default: 0 (Standard auto-detection).
  • Usage: Only modify this if your external barometer is not being detected (Instance 2 or 3 is missing in the GCS).
  • Reboot Required: Yes.

BARO_SPEC_GRAV

Default 1.0
Range 0.5 2.0

Fluid Specific Gravity (BARO_SPEC_GRAV)

Description

BARO_SPEC_GRAV is used by ArduSub (underwater ROVs) to calculate depth.

When a pressure sensor is used underwater, the autopilot translates the pressure into depth based on the density of the water. Fresh water and salt water have different densities, and this parameter allows you to calibrate the depth reading for your specific operating environment.

  • 1.00: Fresh Water.
  • 1.025: Standard Salt Water (Sea water).

The Mathematics

$$ \text{Depth} = \frac{\text{Pressure Difference}}{\rho \times g} $$
where $\rho$ is the water density derived from BARO_SPEC_GRAV.

Tuning & Behavior

  • Default: 1.0.
  • Recommendation: If you are diving in the ocean, change this to 1.025 for the most accurate depth telemetry.
  • Note: This parameter is generally ignored for aerial vehicles.