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_InertialSensor (accessed globally as AP::ins()) is the central library that manages every accelerometer and gyroscope connected to an ArduPilot autopilot. It loads hardware-specific backends at startup, applies calibration offsets and scale factors, runs configurable low-pass and harmonic notch filters, collects delta-angle and delta-velocity integrals for the EKF, and exposes all IMU data through a unified API. The EKF, attitude controller, and vibration monitor all depend on this library.

Supported IMU hardware

ArduPilot ships backend drivers for a broad range of inertial sensors. Detection is automatic based on the hardware definition for the target board.

InvenSense / TDK

MPU-6000, MPU-9250, ICM-20608, ICM-20689, ICM-42688-P, ICM-42605. The ICM-42688 is the most common sensor on modern flight controllers.

Bosch / STMicro

BMI055, BMI088, LSM9DS0, L3GD20. Often found on integrated autopilots where multiple IMU types are fitted for voting.

Analog Devices

ADIS16375, ADIS16470. Tactical-grade IMUs used on high-end platforms where low noise and thermal stability are critical.

Kistler / H3LIS / IIM-42652

High-g accelerometers and specialised sensors for platforms experiencing shock loads above 16 g.

External AHRS

Accepts IMU data forwarded from an external AHRS system (e.g., VectorNav, MicroStrain) through AP_ExternalAHRS.

SITL simulation

A software simulated IMU backend is used in the software-in-the-loop simulator for development and testing.

Key API methods

All IMU data is accessed through the singleton. The primary instance is selected internally; overloads that accept a uint8_t i argument allow per-instance access when multiple IMUs are present.
const Vector3f &get_gyro(void) const;
const Vector3f &get_gyro(uint8_t i) const;
Returns the current filtered gyroscope reading for the primary (or specified) instance in radians per second in body frame (roll rate, pitch rate, yaw rate).
const Vector3f &get_accel(void) const;
const Vector3f &get_accel(uint8_t i) const;
Returns the current filtered accelerometer reading in m/s² in body frame. At rest on a level surface, the Z axis reads approximately +9.81 m/s² (gravity).
bool get_delta_angle(Vector3f &delta_angle, float &delta_angle_dt) const;
bool get_delta_angle(uint8_t i, Vector3f &delta_angle, float &delta_angle_dt) const;
Returns the rotation integral (radians) accumulated since the last update() call and the time interval over which it was collected (delta_angle_dt in seconds). Used directly by the EKF for attitude prediction. Returns false if no new data is available.
bool get_delta_velocity(Vector3f &delta_velocity, float &delta_velocity_dt) const;
bool get_delta_velocity(uint8_t i, Vector3f &delta_velocity, float &delta_velocity_dt) const;
Returns the velocity change integral (m/s) accumulated since the last update() and the corresponding time interval. Used by the EKF for velocity and position prediction. Returns false if no new data is available.
bool get_gyro_health(void) const;
bool get_gyro_health(uint8_t instance) const;
bool get_accel_health(void) const;
bool get_accel_health(uint8_t instance) const;
Returns true if the specified sensor is producing valid data and has not exceeded its error threshold. get_gyro_health_all() and get_accel_health_all() check every registered instance.
bool healthy(void) const;
Convenience method — returns true only when both the primary gyro and the primary accel are healthy. Used in pre-arm checks and failsafe monitoring.
uint8_t get_gyro_count(void) const;
uint8_t get_accel_count(void) const;
Returns the number of registered gyro and accel instances, respectively. On a Pixhawk 6C this is typically 3.
uint16_t get_gyro_rate_hz(uint8_t instance) const;
uint16_t get_accel_rate_hz(uint8_t instance) const;
Returns the effective sample rate in Hz for the given instance, accounting for any internal over-sampling multiplier used by the backend.
Vector3f get_vibration_levels(void) const;
Vector3f get_vibration_levels(uint8_t instance) const;
Returns the RMS vibration magnitude on each body axis in m/s². High vibration (above ~15 m/s²) degrades EKF performance and can cause altitude oscillations.

Sampling rates and filtering

AP_InertialSensor is initialised with a target loop rate and automatically configures backends to over-sample and then filter down to the requested rate.
// Initialise for a 400 Hz main loop (typical for copters)
AP::ins().init(400);
Two filter stages are applied in sequence:
1

Low-pass filter

A second-order Butterworth filter with cutoff frequency set by INS_GYRO_FILTER (gyro) and INS_ACCEL_FILTER (accel). Default is 20 Hz for gyro on most vehicles. Lower values reduce noise but increase phase lag, which can affect attitude control.
2

Harmonic notch filter

One or more harmonic notch filters (INS_HNTCH_* parameters) can be layered on top of the low-pass filter to attenuate motor or rotor harmonics at run-time. The notch frequency can track RPM from ESC telemetry, FFT analysis, or a fixed frequency.
For multirotors, enable the harmonic notch filter (INS_HNTCH_ENABLE 1) and set the mode to ESC RPM tracking (INS_HNTCH_MODE 3) to dynamically attenuate motor noise without excessive phase lag.

IMU calibration

Accelerometer calibration (ACCEL_CAL)

ArduPilot uses a Gauss-Newton six-position calibration routine to compute per-axis offset and scale factor for each accelerometer. Calibration is performed through Mission Planner, QGroundControl, or the MAVLink MAV_CMD_PREFLIGHT_CALIBRATION command. Calibration data is stored in the INS_ACC*_* parameter group and applied automatically at startup.
INS_ACCOFFS_X / Y / Z   — offset vector (m/s²)
INS_ACCSCL_X / Y / Z    — scale factors
INS_ACC2OFFS_* / INS_ACC3OFFS_*  — per-instance offsets

Gyroscope calibration

Gyro offsets are re-estimated at every startup from a 5-second still period (controlled by INS_GYRO_CAL). The offsets are stored in INS_GYROFFS_* parameters.
Temperature calibration (INS_TCAL_*) can be enabled to compensate for bias drift across temperature ranges, which is important on vehicles that fly in varying ambient temperatures.

Multiple IMU voting

When several IMUs are present, the EKF runs a separate prediction lane for each one (controlled by EK3_IMU_MASK). The IMU health flags reported by get_gyro_health() and get_accel_health() allow faulty sensors to be excluded. The INS_USE parameter controls which IMU instances are included in the primary data path:
INS_USE bitEffect
1Include IMU 1 in the active set
2Include IMU 2 in the active set
4Include IMU 3 in the active set
A sensor is promoted as “first usable” (_first_usable_gyro, _first_usable_accel) based on the lowest healthy instance index in the active set.

Usage example

#include <AP_InertialSensor/AP_InertialSensor.h>

void example_ins_read()
{
    AP_InertialSensor &ins = AP::ins();

    // Check overall health before using data
    if (!ins.healthy()) {
        return;
    }

    // Primary filtered gyro reading (rad/s)
    const Vector3f &gyro = ins.get_gyro();
    float roll_rate  = gyro.x;  // rad/s
    float pitch_rate = gyro.y;  // rad/s
    float yaw_rate   = gyro.z;  // rad/s

    // Primary filtered accel reading (m/s²)
    const Vector3f &accel = ins.get_accel();

    // Delta-angle integral for EKF (preferred over raw gyro)
    Vector3f delta_angle;
    float delta_angle_dt;
    if (ins.get_delta_angle(delta_angle, delta_angle_dt)) {
        // delta_angle in radians, delta_angle_dt in seconds
    }

    // Delta-velocity integral for EKF
    Vector3f delta_vel;
    float delta_vel_dt;
    if (ins.get_delta_velocity(delta_vel, delta_vel_dt)) {
        // delta_vel in m/s, delta_vel_dt in seconds
    }

    // Per-instance health and rate
    for (uint8_t i = 0; i < ins.get_gyro_count(); i++) {
        bool gyro_ok = ins.get_gyro_health(i);
        uint16_t rate_hz = ins.get_gyro_rate_hz(i);
    }

    // Vibration monitor
    Vector3f vibe = ins.get_vibration_levels();
}
ParameterDescription
INS_GYRO_FILTERGyro low-pass filter cutoff frequency (Hz)
INS_ACCEL_FILTERAccel low-pass filter cutoff frequency (Hz)
INS_GYRO_CALGyro calibration timing (0 = never, 1 = startup only)
INS_USE / INS_USE2 / INS_USE3Enable/disable individual IMU instances
INS_FAST_SAMPLEBitmask enabling high-rate sensor sampling per instance
INS_HNTCH_ENABLEEnable harmonic notch filter
INS_HNTCH_FREQNotch centre frequency (Hz)
INS_HNTCH_MODENotch tracking mode (fixed, throttle, RPM, FFT)
INS_ACCOFFS_*Accelerometer offset calibration values
INS_ACCSCL_*Accelerometer scale calibration values
INS_GYROFFS_*Gyro offset calibration values

Build docs developers (and LLMs) love