Skip to main content

Documentation Index

Fetch the complete documentation index at: https://mintlify.com/Ardupilot/ardupilot/llms.txt

Use this file to discover all available pages before exploring further.

AP_Baro is the front-end library that manages every barometric pressure sensor attached to an ArduPilot autopilot. It loads the correct backend driver at startup, performs ground-level calibration, applies temperature compensation, optionally corrects for aerodynamic pressure induced by airspeed or propeller wash, and exposes altitude, pressure, and temperature to the rest of the flight stack. The EKF, AHRS, and all altitude-holding flight modes consume baro data exclusively through this interface.

Supported sensors

ArduPilot detects and loads barometer drivers automatically at boot. The following hardware is supported:

MS5611 / MS5607 / MS5637

High-resolution sensors widely used on Pixhawk-family flight controllers. MS5607 mode is selectable via the BARO_OPTIONS parameter.

BMP280 / BMP388 / BMP581

Bosch sensors common on budget and integrated boards. BMP388 and BMP581 offer improved noise characteristics.

SPL06 / DPS310

Infineon/XENSIV sensors with low noise floor, used in newer autopilots and companion boards.

LPS25H / FBM320 / MS5837

Specialised sensors including the MS5837 for underwater depth measurement on ArduSub platforms.

DroneCAN

Receives barometer data over a CAN bus from DroneCAN peripheral nodes.

External AHRS / MSP

Accepts baro data forwarded from an external AHRS system or MSP telemetry source.
The flight controller’s internal barometer is probed first. External I²C barometers can be enabled by setting bits in the BARO_PROBE_EXT bitmask parameter. Up to three barometer instances (BARO_MAX_INSTANCES = 3) can run simultaneously.

Calibration

AP_Baro calibrates on the ground before arming. Calibration records the current pressure and temperature as the reference point, so all subsequent altitude readings are relative to the takeoff location.
// Called once at startup (with save=true to persist ground pressure)
AP::baro().calibrate(true);
Calibration sets ground_pressure for each instance. After calibration, get_altitude() returns altitude relative to that ground pressure using the International Standard Atmosphere (ISA) model. Call update_calibration() to refresh the reference point in-flight (used by some modes to correct baro drift).
Never call calibrate() while airborne. Doing so will reset the altitude reference to the current in-flight pressure and cause large altitude jumps in the EKF.

Key API methods

Access the global instance through AP::baro(). Methods with no argument use the primary barometer; most have an overload that accepts a uint8_t instance index.
float get_altitude(void) const;
float get_altitude(uint8_t instance) const;
Returns altitude in metres relative to the ground pressure recorded during calibration. Positive values are above the calibration point.
float get_altitude_AMSL(void) const;
float get_altitude_AMSL(uint8_t instance) const;
Returns get_altitude() plus the GND_ALT_OFFSET field elevation parameter. Useful when the launch site elevation above MSL is known.
float get_pressure(void) const;
float get_pressure(uint8_t instance) const;
Returns the current barometric pressure in Pascals. Divide by 100 for hectopascals (hPa / mbar).
float get_temperature(void) const;
float get_temperature(uint8_t instance) const;
Returns the on-chip temperature in degrees Celsius. Used internally for temperature compensation and also available as a diagnostic.
float get_climb_rate(void);
Returns the estimated vertical speed in m/s derived from a derivative filter applied to get_altitude(). Positive values indicate climbing. This is a raw baro-only estimate; prefer the EKF climb rate for flight control.
bool healthy(void) const;
bool healthy(uint8_t instance) const;
bool all_healthy(void) const;
Returns true if the sensor has produced a reading within the last 500 ms (BARO_TIMEOUT_MS). all_healthy() checks every registered instance.
uint8_t num_instances(void) const;
Returns the number of barometer backends that successfully registered during init().
float get_ground_pressure(void) const;
float get_ground_temperature(void) const;
Returns the pressure (Pa) and temperature (°C) captured at the time of the last calibrate() call. Valid only after calibration.

Airspeed and wind pressure correction

In fast-moving aircraft the static port is affected by dynamic pressure from airspeed and propeller thrust, causing the barometer to read a false altitude. AP_Baro supports two compensation mechanisms:
Applies a correction proportional to dynamic pressure derived from the vehicle’s airspeed vector. The scaling coefficients are tuned per axis via the GND_WCOEF_* parameter group.
// Corrected pressure accessed via:
float p_corrected = AP::baro().get_corrected_pressure(instance);

Atmospheric model

AP_Baro implements the 1976 US Standard Atmosphere model for altitude–pressure conversion. Helper functions are available for SITL and advanced use:
// Convert a pressure reading to an altitude (m AMSL)
float alt = AP::baro().get_altitude_from_pressure(pressure_pa);

// Equivalent airspeed to true airspeed scale factor
float eas2tas = AP::baro()._get_EAS2TAS();

Usage example

#include <AP_Baro/AP_Baro.h>

void example_baro_read()
{
    AP_Baro &baro = AP::baro();

    // Always check health before using data
    if (!baro.healthy()) {
        return;
    }

    // Relative altitude above takeoff point (metres)
    float alt_m = baro.get_altitude();

    // Raw pressure in Pascals
    float pressure_pa = baro.get_pressure();

    // Sensor temperature in °C
    float temp_c = baro.get_temperature();

    // Vertical climb rate (m/s, positive = climbing)
    float climb = baro.get_climb_rate();

    // Iterate over all registered barometers
    for (uint8_t i = 0; i < baro.num_instances(); i++) {
        if (baro.healthy(i)) {
            float alt_i = baro.get_altitude(i);
        }
    }
}

Multiple barometers and primary selection

When more than one barometer is registered, AP_Baro designates a primary instance. You can override it with the BARO_PRIMARY parameter or call set_primary_baro() programmatically.
// Force instance 1 as primary
AP::baro().set_primary_baro(1);

// Read primary instance index
uint8_t primary = AP::baro().get_primary();
The EKF reads the primary barometer for altitude fusion. A healthy second barometer is visible in the logs but is not automatically fused unless EK3_ALT_SOURCE is changed and the EKF is reconfigured.
ParameterDescription
BARO_PRIMARYPrimary barometer instance index
BARO_PROBE_EXTBitmask enabling external I²C barometer probing
GND_ALT_OFFSETField elevation offset for AMSL altitude
GND_TEMPUser override of ground temperature for EAS2TAS
BARO_FILTEROutlier rejection filter range (in standard deviations)
GND_WCOEF_*Wind-induced pressure correction coefficients
GND_TCOMP_SCALEThrust-compensation pressure scaling factor
BARO_OPTIONSOption flags (e.g., treat MS5611 as MS5607)

Build docs developers (and LLMs) love