MAVLINKHUD

Overview

The INS parameter group is the core configuration for the Inertial Sensors (Accelerometers and Gyroscopes). This library is responsible for sampling raw sensor data, applying calibrations, and filtering the results before they are consumed by the EKF (State Estimator) and PID controllers.

This is the most critical system for flight stability. If the INS data is noisy or incorrectly calibrated, the vehicle cannot fly.

Key Concepts

1. Calibration (Offsets & Scaling)

Every IMU has manufacturing imperfections (e.g., when the drone is still, the accel might read 0.05m/s² instead of 0).

  • Offsets (_OFFS): Shift the zero point.
  • Scaling (_SCAL): Ensures that 1G of gravity actually measures as 9.81m/s².

2. Harmonic Notch Filters (INS_HNTCH_...)

This is a modern ArduPilot feature that uses a high-Q notch filter to "erase" motor vibration noise.

  • Dynamic Tracking: The filter can follow the motor RPM in real-time (via ESC telemetry or throttle) to target the exact frequency of the propeller noise.
  • Result: Allows for much higher PID gains and a "locked-in" flight feel.

3. Temperature Calibration (INS_TCAL_...)

MEMS sensors drift as they heat up. The TCAL system applies complex polynomial curves to counteract this drift, ensuring a stable horizon from a cold boot to a hot flight.

4. Fast Sampling (INS_FAST_SAMPLE)

Enables pulling data from sensors at 8kHz or 16kHz for better aliasing rejection.

Parameter Breakdown

  • INS_ACC_FILTER: Low-pass filter for accelerometers (Hz).
  • INS_GYRO_FILTER: Low-pass filter for gyroscopes (Hz).
  • INS_ENABLE_MASK: Selects active IMUs.
  • INS_HNTCH_ENABLE: Toggles the harmonic notch.

Integration Guide

Accelerometer Calibration

  1. Level: Place vehicle on a perfectly level surface. Click "Calibrate Level."
  2. 6-Point: Follow the GCS prompts to place the vehicle on each of its 6 sides. This populates the INS_ACCn_OFFS and INS_ACCn_SCAL values.

Tuning the Notch Filter

  1. Log: Fly and record raw IMU data (INS_LOG_BAT_MASK = 1).
  2. Analyze: Use the Mission Planner "FFT" tool to find the noise peak (e.g., 180Hz).
  3. Config: Set INS_HNTCH_FREQ to 180 and INS_HNTCH_BW to 90.

Developer Notes

  • Library: libraries/AP_InertialSensor.
  • Criticality: High. The INS loop runs at the highest priority in the firmware.

INS4_ACC_CALTEMP

degC
Default -300
Range -50 100

Accelerometer 4 Calibration Temperature (INS4_ACC_CALTEMP)

Description

INS4_ACC_CALTEMP records the temperature of the 4th IMU when its accelerometer calibration was performed.

This is part of ArduPilot's support for high-redundancy flight controllers that have 4 or more IMUs. The autopilot uses this value to monitor thermal drift and apply corrections relative to this calibration baseline.

INS4_ACC_ID

Default 0
Range null

Accelerometer ID

Note: This parameter functions identically to INS_ACC_ID.

INS4_GYR_CALTEMP

degC
Default -300
Range -50 100

Gyroscope 4 Calibration Temperature (INS4_GYR_CALTEMP)

Description

INS4_GYR_CALTEMP records the temperature of the 4th IMU when its gyroscope calibration was performed.

INS4_GYR_ID

Default 0
Range null

Gyro ID

Note: This parameter functions identically to INS_GYR_ID.

INS4_USE

Default 1
Range null

Use first IMU for attitude, velocity and position estimates

Note: This parameter functions identically to INS_USE.

INS5_ACC_CALTEMP

Accelerometer 5 Calibration Temperature

Note: This parameter functions identically to INS4_ACC_CALTEMP.

INS5_ACC_ID

Default 0
Range null

Accelerometer ID

Note: This parameter functions identically to INS_ACC_ID.

INS5_GYR_CALTEMP

Gyroscope 5 Calibration Temperature

Note: This parameter functions identically to INS4_GYR_CALTEMP.

INS5_GYR_ID

Default 0
Range null

Gyro ID

Note: This parameter functions identically to INS_GYR_ID.

INS5_USE

Default 1
Range null

Use first IMU for attitude, velocity and position estimates

Note: This parameter functions identically to INS_USE.

INS_ACC1_CALTEMP

degC
Default -300
Range -50 100

Accelerometer 1 Calibration Temperature (INS_ACC1_CALTEMP)

Description

INS_ACC1_CALTEMP records the temperature of the flight controller when you performed the 6-point accelerometer calibration.

The EKF uses this as a reference point. If the current temperature deviates significantly from this value, the system may apply thermal compensation corrections (if INS_TCAL is enabled) to maintain accuracy.

Tuning & Behavior

  • Default Value: -300 (Uncalibrated).
  • Usage: Do not edit manually. This is updated automatically when you run the calibration routine.

INS_ACC2OFFS

null
Default 0
Range null

None

Note: This parameter functions identically to INS_ACCOFFS.

INS_ACC2SCAL

null
Default 1.0
Range null

None

Note: This parameter functions identically to INS_ACCSCAL.

INS_ACC2_CALTEMP

degC
Default -300
Range null

Calibration temperature for 2nd accelerometer

Note: This parameter functions identically to INS_ACC1_CALTEMP.

INS_ACC2_ID

null
Default 0
Range null

None

Note: This parameter functions identically to INS_ACC_ID.

INS_ACC3OFFS

null
Default 0
Range null

None

Note: This parameter functions identically to INS_ACCOFFS.

INS_ACC3SCAL

null
Default 1.0
Range null

None

Note: This parameter functions identically to INS_ACCSCAL.

INS_ACC3_CALTEMP

degC
Default -300
Range null

Calibration temperature for 3rd accelerometer

Note: This parameter functions identically to INS_ACC1_CALTEMP.

INS_ACC3_ID

null
Default 0
Range null

None

Note: This parameter functions identically to INS_ACC_ID.

INS_ACCEL_FILTER

Hz
Default 10
Range 0 250

Accelerometer Low Pass Filter (INS_ACCEL_FILTER)

Description

INS_ACCEL_FILTER removes vibration noise from the accelerometer data.

Unlike the Gyro (which is for attitude), the Accelerometer is primarily for position and climb rate. It is very sensitive to motor vibration.

The Engineer's View

Defined in AP_InertialSensor.cpp.
The filtered accelerometer data is used by the EKF to calculate velocity and position increments.

Tuning & Behavior

  • Default Value: 10 Hz.
  • Recommendation: Usually leave at 10-20 Hz. Setting it higher may improve position hold in high winds, but only if your frame is exceptionally clean (low vibration).

INS_ACCOFFS

$m/s^2$
Default 0
Range -3.5 3.5

Accelerometer Z Offset (INS_ACCOFFS)

Description

INS_ACCOFFS is the result of the accelerometer calibration.

It represents the constant error (bias) in the Z-axis measurement. The flight controller subtracts this value from the raw sensor reading to get the true acceleration.

Tuning & Behavior

  • Default Value: 0.
  • Usage: Do not edit manually. Updated by the AccelCal routine.

INS_ACCSCAL

Default 1.0
Range 0.8 1.2

Accelerometer Z Scale Factor (INS_ACCSCAL)

Description

INS_ACCSCAL corrects the "Gain" of the accelerometer.

If you tip the drone 90 degrees, the Z-axis should read 0G. If it reads 0.1G, the scale factor is wrong. This parameter is calculated automatically during the 6-point calibration to ensuring that 1G really means 1G.

Tuning & Behavior

  • Default Value: 1.0 (No correction).
  • Usage: Automatically updated during calibration.

INS_ACC_BODYFIX

Default 2
Range 0 2

Accelerometer Body Fix (INS_ACC_BODYFIX)

Description

INS_ACC_BODYFIX corrects for physical misalignment of the flight controller.

If your board is mounted slightly crooked, the accelerometers will report a constant error. This parameter enables a correction matrix that rotates the accelerometer vector to match the vehicle's body frame.

Tuning & Behavior

  • 0: Disabled.
  • 1: Use AHRS Trim.
  • 2: Use Board Orientation.

INS_ACC_ID

Default 0

Accelerometer ID (INS_ACC_ID)

Description

INS_ACC_ID is a Read-Only parameter that stores the unique hardware ID of the first accelerometer (Accel 1).

It is used to identify the sensor and associate calibration data (offsets/scaling) with the specific physical hardware.

The Mathematics

See COMPASS_DEV_ID for ID packing details (Bus type, Bus number, Address).

The Engineer's View

Populated during AP_InertialSensor::init().
If set to 0, the system re-detects the sensor on the next boot.
Usually, this ID matches INS_GYR_ID if the accelerometer and gyroscope are part of the same 6-axis IMU chip (e.g., MPU6000, ICM20602), though the dev_type bits might differ slightly depending on the driver implementation.

Tuning & Behavior

  • Default Value: 0 (Auto-Detect)
  • Recommendation: Do not touch. If you replace the flight controller, this will update automatically.

INS_ENABLE_MASK

Default 127
Range 0 127

IMU enable mask (INS_ENABLE_MASK)

Description

INS_ENABLE_MASK allows precise control over which Inertial Measurement Units (IMUs) are detected and initialized by the autopilot at boot.

ArduPilot can support multiple IMUs (typically 3 on high-end boards like the Cube Orange). If a specific IMU sensor hardware is faulty (e.g., "IMU 2 Calibration Failed" persistent error) or is known to be noisy/defective on a particular board revision, you can use this mask to completely hide it from the flight controller.

The Mathematics

$$ \text{Enabled IMUs} = \sum\_{k=0}^{6} (2^k \text{ is set}) \rightarrow \text{IMU } k+1 $$

  • Bit 0 (1): IMU 1
  • Bit 1 (2): IMU 2
  • Bit 2 (4): IMU 3
  • ...

Default is 127 (0x7F), which enables the first 7 possible IMUs (usually only 2 or 3 exist).

The Engineer's View

Used in AP_InertialSensor::detect_backends().
The driver check ADD_BACKEND verifies (1U << probe_count) & enable_mask. If the bit is 0, the driver probe is skipped entirely. This is cleaner than INS_USE_x = 0 because it saves RAM and CPU by not even allocating the backend driver structures.

Tuning & Behavior

  • Default Value: 127 (All Enabled)
  • Use Case:
    • Faulty Sensor: If the GCS says "Bad Gyro Health" for IMU 3 and recalibration doesn't fix it, set INS_ENABLE_MASK to 3 (1 + 2) to disable IMU 3 permanently.
    • Cube Isolated IMU: On the Cube Black/Orange, the isolated IMU (IMU 3) is sometimes disabled for specific industrial applications where the vibration mount causes issues.

INS_FAST_SAMPLE

Default 1
Range 0 7

Fast sampling mask (INS_FAST_SAMPLE)

Description

INS_FAST_SAMPLE is a bitmask that determines which IMUs are allowed to run at the higher INS_GYRO_RATE (e.g., 2kHz, 4kHz, 8kHz).

  • Bit 0: IMU 1
  • Bit 1: IMU 2
  • Bit 2: IMU 3

If a bit is set (1), that IMU attempts to run at INS_GYRO_RATE.
If a bit is clear (0), that IMU runs at the standard 1kHz (or default backend rate).

The Mathematics

$$ \text{Sample Rate}\_i = \begin{cases} \text{INS\_GYRO\_RATE} & \text{if bit } i \text{ is set} \ 1\text{kHz} & \text{otherwise} \end{cases} $$

The Engineer's View

Default behavior depends on the board (HAL_DEFAULT_INS_FAST_SAMPLE).
Typically, the primary IMU (Bit 0) is enabled for fast sampling to feed the low-latency control loop. Secondary IMUs might be left slow to save CPU or reduce noise aliasing.

Tuning & Behavior

  • Default Value: 1 (IMU 1 Fast)
  • Recommendation:
    • 1 (IMU 1 only): Good for most setups.
    • 3 (IMU 1 & 2): If you want redundancy and EKF lane switching to have equal performance on both sensors.
    • 7 (All): Max performance, max CPU usage.

INS_GYR1_CALTEMP

degC
Default -300
Range -50 100

Gyroscope 1 Calibration Temperature (INS_GYR1_CALTEMP)

Description

INS_GYR1_CALTEMP records the board temperature during gyro calibration.

Gyroscopes are sensitive to temperature changes. Knowing the temperature at which the zero-offset was determined allows the flight controller to better predict and correct for bias drift as the drone warms up or cools down.

Tuning & Behavior

  • Default Value: -300 (Uncalibrated).
  • Usage: Automatically updated during calibration.

INS_GYR2OFFS

null
Default 0
Range null

None

Note: This parameter functions identically to INS_GYROFFS.

INS_GYR2_CALTEMP

degC
Default -300
Range null

Calibration temperature for 2nd gyroscope

Note: This parameter functions identically to INS_GYR1_CALTEMP.

INS_GYR2_ID

null
Default 0
Range null

None

Note: This parameter functions identically to INS_GYR_ID.

INS_GYR3OFFS

null
Default 0
Range null

None

Note: This parameter functions identically to INS_GYROFFS.

INS_GYR3_CALTEMP

degC
Default -300
Range null

Calibration temperature for 3rd gyroscope

Note: This parameter functions identically to INS_GYR1_CALTEMP.

INS_GYR3_ID

null
Default 0
Range null

None

Note: This parameter functions identically to INS_GYR_ID.

INS_GYROFFS

rad/s
Default 0
Range -0.1 0.1

Gyroscope Z Offset (INS_GYROFFS)

Description

INS_GYROFFS is the result of the gyro calibration.

When you boot the drone, it must sit perfectly still for a few seconds. During this time, the flight controller averages the gyro readings to find the "Zero" point. This value is stored here to correct for sensor drift.

Tuning & Behavior

  • Default Value: 0.
  • Usage: Updated automatically on every boot. Do not change manually.

INS_GYRO_FILTER

Hz
Default 20
Range 0 250

Gyroscope Low Pass Filter (INS_GYRO_FILTER)

Description

INS_GYRO_FILTER sets the "Smoothness" of the raw gyroscope data.

All sensors produce high-frequency electrical and mechanical noise (vibration). This low-pass filter removes that noise before the autopilot uses the data for attitude control.

  • Higher Frequency (e.g., 40Hz): Less delay (lower latency), but more noise gets through. Best for small, clean racing quads.
  • Lower Frequency (e.g., 10Hz): Very smooth data, but adds delay. Best for large, vibey industrial drones.

The Mathematics

This is a standard 2nd-order software Butterworth filter. The signal $y$ is calculated from the input $x$ using the cutoff frequency $f\_c$:

$$ y\_n = \text{Butterworth}(x\_n, f\_c) $$

Lowering $f\_c$ increases the group delay (latency) of the signal, which can destabilize the PID controller if set too low.

The Engineer's View

Defined in AP_InertialSensor.cpp.
The filtered gyro data is the primary input to the Rate PID loop. Delay here is "bad" for performance but necessary for stability.

Tuning & Behavior

  • Default Value: 20 Hz.
  • Small Quads (5-7 inch): Try 30Hz to 60Hz.
  • Large Quads (15 inch+): Try 10Hz to 20Hz.
  • Harmonic Notch: If you have persistent motor noise, do not lower this filter excessively; use the INS_HNTCH (Harmonic Notch) system instead.

INS_GYRO_RATE

Default 0
Range 0 3

Gyro rate for IMUs with Fast Sampling enabled (INS_GYRO_RATE)

Description

INS_GYRO_RATE sets the loop rate of the sensor backend. This is not the main flight control loop rate (which is usually 400Hz or 800Hz), but the rate at which the sensor driver reads data from the IMU chip.

  • 0: 1kHz (Default). Standard rate. Good for older boards.
  • 1: 2kHz. Required for good Harmonic Notch filtering on most quads.
  • 2: 4kHz. Higher precision, lower latency. Requires a fast CPU (F7/H7).
  • 3: 8kHz. Ultra-low latency. Only for high-performance H7 boards.

The Mathematics

The sensor backend runs a loop:

  1. Read Gyro at INS_GYRO_RATE.
  2. Apply Hardware LPF (if configured on chip).
  3. Apply Harmonic Notch Filter.
  4. Apply INS_GYRO_FILTER (Software LPF).
  5. Downsample to Main Loop Rate (e.g., average 8 samples if running 8kHz sensor and 1kHz loop).

The Engineer's View

Sets _fast_sampling_rate in AP_InertialSensor.
To use the Harmonic Notch Filter effectively, the sampling rate must be at least 2x the highest frequency you want to filter (Nyquist Theorem).
If you want to filter noise at 400Hz (2nd harmonic of a 200Hz motor), you need at least 800Hz sampling. In practice, 2kHz is the recommended minimum for notch filtering to avoid aliasing.

Tuning & Behavior

  • Default Value: 0 (1kHz)
  • Recommendation:
    • Set to 1 (2kHz) or 2 (4kHz) on modern boards (Cube Orange, Matek H743).
    • This provides a dense stream of data for the filters to work with, resulting in a cleaner signal for the PID loop.
  • Warning: Higher rates consume more CPU. Check LOAD in MAVLink messages. If it exceeds 80%, lower this rate.

INS_GYR_CAL

Default 1
Range 0 1

Gyro Calibration scheme (INS_GYR_CAL)

Description

INS_GYR_CAL determines if the autopilot should re-calibrate the gyroscope offsets every time it boots.

  • 0: Never. Relies on saved offsets. Fast boot, but risky if temperature changes significantly.
  • 1: Start-up only (Default). Calibrates every time you plug in the battery. Requires the drone to be still during startup.

The Mathematics

The calibration routine calculates the mean value of the gyro output while the vehicle is stationary (assumed 0 rotation) and subtracts this as a bias.
$$ \vec{\omega}{cal} = \vec{\omega}{raw} - \vec{\omega}\_{bias} $$

The Engineer's View

If set to 1, AP_InertialSensor::init() calls _init_gyro() which blocks startup until the gyros are stable. This is why you see "Calibrating IMU..." on the HUD.
If set to 0, it skips this and uses the INS_GYR_OFFS parameters stored in EEPROM.

Tuning & Behavior

  • Default Value: 1
  • Recommendation: Leave at 1.
  • Boat Mode: If launching from a moving boat, you must set this to 0 (Never), otherwise the calibration will fail or learn a huge bias (thinking the boat's motion is "still"), causing the drone to flip on takeoff. You must perform a good calibration on land first.

INS_GYR_ID

Default 0

Gyro ID (INS_GYR_ID)

Description

INS_GYR_ID is a Read-Only parameter that stores the unique hardware ID of the first gyroscope (Gyro 1).

See INS_ACC_ID for details on ID structure.

The Mathematics

See COMPASS_DEV_ID.

The Engineer's View

See INS_ACC_ID.

Tuning & Behavior

  • Default Value: 0 (Auto-Detect)

INS_HNTC2_ATT

dB
Default 40
Range 5 50

Harmonic Notch Filter attenuation

Note: This parameter functions identically to INS_HNTCH_ATT for a secondary notch instance.

INS_HNTC2_BW

Hz
Default 40
Range 5 250

Harmonic Notch Filter bandwidth

Note: This parameter functions identically to INS_HNTCH_BW for a secondary notch instance.

INS_HNTC2_ENABLE

null
Default 0
Range null

Enable pullup after altitude wait

Note: This parameter functions identically to INS_HNTCH_ENABLE for a secondary notch instance.

INS_HNTC2_FM_RAT

null
Default 1.0
Range 0.1 1.0

Throttle notch min freqency ratio

Note: This parameter functions identically to INS_HNTCH_FM_RAT for a secondary notch instance.

INS_HNTC2_FREQ

null
Default 0
Range 1000 6000

Video Transmitter Frequency

Note: This parameter functions identically to INS_HNTCH_FREQ for a secondary notch instance.

INS_HNTC2_HMNCS

null
Default 3
Range null

Harmonic Notch Filter harmonics

Note: This parameter functions identically to INS_HNTCH_HMNCS for a secondary notch instance.

INS_HNTC2_MODE

null
Default (int8_t
Range null

Rotor Speed Control Mode

Note: This parameter functions identically to INS_HNTCH_MODE.

INS_HNTC2_OPTS

null
Default 0
Range null

Harmonic Notch Filter options

Note: This parameter functions identically to INS_HNTCH_OPTS for a secondary notch instance.

INS_HNTC2_REF

null
Default 0
Range 0.0 1.0

Harmonic Notch Filter reference value

Note: This parameter functions identically to INS_HNTCH_REF for a secondary notch instance.

INS_HNTC3_ATT

dB
Default 40
Range 5 50

Harmonic Notch Filter attenuation

Note: This parameter functions identically to INS_HNTCH_ATT for a secondary notch instance.

INS_HNTC3_BW

Hz
Default 40
Range 5 250

Harmonic Notch Filter bandwidth

Note: This parameter functions identically to INS_HNTCH_BW for a secondary notch instance.

INS_HNTC3_ENABLE

null
Default 0
Range null

Enable pullup after altitude wait

Note: This parameter functions identically to INS_HNTCH_ENABLE for a secondary notch instance.

INS_HNTC3_FM_RAT

null
Default 1.0
Range 0.1 1.0

Throttle notch min freqency ratio

Note: This parameter functions identically to INS_HNTCH_FM_RAT for a secondary notch instance.

INS_HNTC3_FREQ

null
Default 0
Range 1000 6000

Video Transmitter Frequency

Note: This parameter functions identically to INS_HNTCH_FREQ for a secondary notch instance.

INS_HNTC3_HMNCS

null
Default 3
Range null

Harmonic Notch Filter harmonics

Note: This parameter functions identically to INS_HNTCH_HMNCS for a secondary notch instance.

INS_HNTC3_MODE

null
Default (int8_t
Range null

Rotor Speed Control Mode

Note: This parameter functions identically to INS_HNTCH_MODE.

INS_HNTC3_OPTS

null
Default 0
Range null

Harmonic Notch Filter options

Note: This parameter functions identically to INS_HNTCH_OPTS for a secondary notch instance.

INS_HNTC3_REF

null
Default 0
Range 0.0 1.0

Harmonic Notch Filter reference value

Note: This parameter functions identically to INS_HNTCH_REF for a secondary notch instance.

INS_HNTC4_ATT

dB
Default 40
Range 10 100

Harmonic Notch Filter 4 Attenuation (INS_HNTC4_ATT)

Description

INS_HNTC4_ATT determines how aggressively the fourth filter removes noise.

Tuning & Behavior

  • Default Value: 40 dB.
  • Recommendation: Leave at 40.

INS_HNTC4_BW

Hz
Default 40
Range 10 250

Harmonic Notch Filter 4 Bandwidth (INS_HNTC4_BW)

Description

INS_HNTC4_BW sets the width of the notch for the fourth filter.

Tuning & Behavior

  • Default Value: 40 Hz.
  • Recommendation: Set to half of INS_HNTC4_FREQ.

INS_HNTC4_ENABLE

Default 0
Range 0 1

Harmonic Notch Filter 4 Enable (INS_HNTC4_ENABLE)

Description

INS_HNTC4_ENABLE turns on an additional dynamic filter.

Most drones only need one or two notch filters. However, complex multi-rotor setups (like a dodecacopter) or frames with multiple vibration sources might need a fourth filter to clean up the gyro signal completely.

Tuning & Behavior

  • 0: Disabled.
  • 1: Enabled.

INS_HNTC4_FM_RAT

null
Default 1.0
Range 0.1 1.0

Throttle notch min freqency ratio

Note: This parameter functions identically to INS_HNTCH_FM_RAT.

INS_HNTC4_FREQ

Hz
Default 80
Range 10 500

Harmonic Notch Filter 4 Frequency (INS_HNTC4_FREQ)

Description

INS_HNTC4_FREQ sets the target frequency for the fourth notch filter.

ArduPilot allows you to stack multiple notch filters. You might use Filter 1 (HNTCH) for the motors, and Filter 2 (HNTC2) for a specific frame resonance. Filter 4 provides yet another layer of surgical noise removal.

  • Static Mode: This is the fixed frequency to remove.
  • Dynamic Mode: This is the reference frequency at the reference throttle/RPM.

Tuning & Behavior

  • Default Value: 80 Hz.
  • Recommendation: Use this only if you have a complex noise profile with multiple independent peaks that Filters 1, 2, and 3 couldn't handle.

INS_HNTC4_HMNCS

Default 1
Range 0 31

Harmonic Notch Filter 4 Harmonics (INS_HNTC4_HMNCS)

Description

INS_HNTC4_HMNCS tells the filter to target multiples of the base frequency.

  • Bit 0 (1): Fundamental frequency (1x).
  • Bit 1 (2): 2nd Harmonic (2x).
  • Bit 2 (4): 3rd Harmonic (3x).

Tuning & Behavior

  • Default Value: 1 (Base freq only).
  • Recommendation: Set to 3 (1st + 2nd) or 7 (1st + 2nd + 3rd) if your FFT shows multiple spikes.

INS_HNTC4_MODE

Default 0
Range 0 4

Harmonic Notch Filter 4 Dynamic Mode (INS_HNTC4_MODE)

Description

INS_HNTC4_MODE tells the fourth filter how to move.

  • 0: Fixed frequency.
  • 1: Throttle-based tracking.
  • 2: RPM Sensor.
  • 3: ESC Telemetry.
  • 4: Dynamic FFT.

Tuning & Behavior

  • Default Value: 0.

INS_HNTC4_OPTS

null
Default 0
Range null

Harmonic Notch Filter options

Note: This parameter functions identically to INS_HNTCH_OPTS.

INS_HNTC4_REF

Default 0
Range 0 1.0

Harmonic Notch Filter 4 Reference (INS_HNTC4_REF)

Description

INS_HNTC4_REF scales the dynamic frequency for the fourth filter.

Tuning & Behavior

  • Default Value: 0.
  • Usage: Set to Hover Throttle if using Mode 1.

INS_HNTCH_ATT

dB
Default 40
Range 5 50

Harmonic Notch Filter attenuation (INS_HNTCH_ATT)

Description

INS_HNTCH_ATT sets how "deep" the cut is. A higher dB value means more noise removal.

  • 15-20 dB: Mild filtering. Good for slightly noisy frames.
  • 40 dB (Default): Deep filtering. Removes almost 99% of the noise at the center frequency.
  • > 40 dB: Very sharp, deep notch. Can cause phase issues if the bandwidth is too narrow.

The Mathematics

Attenuation $A$ determines the filter coefficient calculations.
$$ \text{Gain} = 10^{-A/20} $$
At 40dB, the gain at the center frequency is $0.01$.

The Engineer's View

Used in NotchFilter::calculate_A_and_Q.
Higher attenuation increases the "sharpness" of the phase transition around the notch.

Tuning & Behavior

  • Default Value: 40 dB
  • Recommendation: Default is usually fine.
    • If the filter is causing latency issues (oscillations), try reducing this to 20 or 30 dB.
    • If noise is still getting through, increasing this rarely helps; instead, increase INS_HNTCH_BW (Bandwidth).

INS_HNTCH_BW

Hz
Default 40
Range 5 250

Harmonic Notch Bandwidth (INS_HNTCH_BW)

Description

INS_HNTCH_BW sets the "width" of the frequency gap that the notch filter removes.

Imagine the Notch Filter as a "V" shape cut out of the vibration graph.

  • The Bottom of the V is the Center Frequency (INS_HNTCH_FREQ).
  • The Width of the V is controlled by this Bandwidth parameter.

A wider bandwidth catches more noise (especially if your motors are changing speed rapidly), but it also introduces more Latency (Delay) into the flight controller. Too much delay will make the drone wobble or oscillate.

The Mathematics

The quality factor ($Q$) of the filter is derived from the ratio of the center frequency ($f\_c$) to the bandwidth ($BW$):

$$ Q = \frac{f\_c}{BW} $$

A lower bandwidth results in a higher $Q$ (sharper notch, less delay).
A higher bandwidth results in a lower $Q$ (wider notch, more delay).

For dynamic harmonic notch filters, the bandwidth scales with the frequency to maintain a constant $Q$. This means if your motor frequency doubles, the notch becomes twice as wide to catch the noise.

The Engineer's View

Defined in AP_InertialSensor.
This parameter sets the -3dB cutoff points relative to the center frequency.
If INS_HNTCH_BW is set to 40Hz and INS_HNTCH_FREQ is 80Hz:

  • The filter will aggressively attenuate noise between approximately 60Hz and 100Hz.
  • The phase lag introduced by the filter is directly proportional to the depth and width of the notch.

Tuning & Behavior

  • Default Value: 40 Hz.
  • Golden Rule: Set this to half of your Center Frequency.
    • If INS_HNTCH_FREQ = 80Hz, set INS_HNTCH_BW = 40Hz.
    • If INS_HNTCH_FREQ = 200Hz (small racing quad), set INS_HNTCH_BW = 100Hz.
  • Warning: Setting INS_HNTCH_BW larger than INS_HNTCH_FREQ is invalid and can cause filter instability.

INS_HNTCH_ENABLE

Default 0
Range 0 1

Harmonic Notch Filter Enable (INS_HNTCH_ENABLE)

Description

INS_HNTCH_ENABLE activates the most advanced vibration-fighting tool in ArduPilot: the Harmonic Notch Filter.

Standard low-pass filters are like a broad-brush; they smooth everything. A Notch Filter is like a scalpel; it targets one specific frequency (the one caused by your spinning motors) and removes it while leaving everything else untouched.

Enabling this allows the drone to ignore the "buzz" of its own motors, leading to much cooler motors and smoother flight.

The Engineer's View

Defined in AP_InertialSensor.cpp.
When enabled, the autopilot allocates resources for a dynamically-tuned notch filter on the gyroscope data path. This filter is placed after the raw sampling but before the Rate PIDs.

Tuning & Behavior

  • Default Value: 0 (Disabled)
  • Recommendation: Every serious drone pilot should enable this. It is a game-changer for flight quality.
  • Reboot Required: Yes.

INS_HNTCH_FM_RAT

Default 1.0
Range 0.1 1.0

Throttle notch min freqency ratio (INS_HNTCH_FM_RAT)

Description

INS_HNTCH_FM_RAT prevents the filter frequency from dropping too low when you lower the throttle.

  • 1.0 (Default): The filter never drops below INS_HNTCH_FREQ.
  • < 1.0: The filter can drop to FREQ * FM_RAT.

This is important because filtering at very low frequencies (e.g., < 40Hz) introduces massive phase lag (delay) that can destabilize the drone.

The Mathematics

$$ f\_{min\_limit} = \text{INS\_HNTCH\_FREQ} \times \text{INS\_HNTCH\_FM\_RAT} $$
$$ f\_{actual} = \max(f\_{calculated}, f\_{min\_limit}) $$

The Engineer's View

Used in HarmonicNotchFilter::update().
It clamps the lower bound of the center frequency.

Tuning & Behavior

  • Default Value: 1.0
  • Range: 0.1 - 1.0
  • Recommendation: Leave at 1.0 if using Throttle Reference.
  • Exception: If you set INS_HNTCH_FREQ to your hover frequency (Throttle Mode), you might want to allow the filter to drop slightly during descent (low throttle). Set to 0.7 to allow it to track down to 70% of hover RPM.

INS_HNTCH_FREQ

Hz
Default 80
Range 10 500

Harmonic Notch Center Frequency (INS_HNTCH_FREQ)

Description

INS_HNTCH_FREQ defines the primary frequency of the noise you want to remove.

For most drones, this corresponds to the rotation speed of the motors (in rotations per second) during a steady hover. By targeting this specific frequency, the filter removes the vibration caused by the spinning props before it reaches the flight controller.

The Mathematics

$$ \text{Frequency (Hz)} = \frac{\text{RPM}}{60} $$

If your motors hover at 6000 RPM:
$$ \text{INS\_HNTCH\_FREQ} = \frac{6000}{60} = 100 \text{ Hz} $$

If you use Dynamic Harmonic Notch (e.g. Throttle or ESC based), this parameter acts as the minimum lower bound or the reference frequency for the configuration.

The Engineer's View

This parameter sets the $f\_c$ (center cutoff) for the digital filter.
In "Static Mode" (INS_HNTCH_MODE = 0), the filter stays fixed at this frequency.
In "Dynamic Mode", the filter moves. However, INS_HNTCH_FREQ is still used to calculate the initial Quality Factor ($Q$) in conjunction with INS_HNTCH_BW.

Tuning & Behavior

  • Default Value: 80 Hz.
  • **How to find it:
    1. Set INS_LOG_BAT_MASK = 1 (IMU Pre-Filter).
    2. Do a hover flight.
    3. Download the DataFlash log.
    4. Run an FFT (Fast Fourier Transform) on the GYRO[0].GyrX data.
    5. Look for the biggest spike in the graph. That X-axis value is your Frequency.

INS_HNTCH_HMNCS

Default 3
Range 0 65535

Harmonic Notch Filter harmonics (INS_HNTCH_HMNCS)

Description

INS_HNTCH_HMNCS is a bitmask that tells the filter which multiples of the base frequency to target.

  • Bit 0 (1): 1st Harmonic (Base Frequency).
  • Bit 1 (2): 2nd Harmonic ($2 \times F$).
  • Bit 2 (4): 3rd Harmonic ($3 \times F$).
  • ...

Default is 3 (1 + 2), meaning it filters the Base Frequency and the 2nd Harmonic.

The Mathematics

$$ \text{Active Filters} = \sum\_{k=0}^{15} (2^k \text{ is set}) \rightarrow \text{Filter at } (k+1) \cdot f\_0 $$

The Engineer's View

Each set bit allocates a new NotchFilter object.
Allocating too many harmonics (e.g., setting it to 255) consumes CPU and memory.
For typical multicopters, the energy is concentrated in the 1st, 2nd, and sometimes 4th harmonic.

Tuning & Behavior

  • Default Value: 3 (1st and 2nd Harmonics)
  • Recommendation:
    • 3 (1st + 2nd): Good for most quads.
    • 1 (1st only): If CPU is tight or noise is simple.
    • 7 (1st + 2nd + 3rd): If spectrogram shows a 3rd peak.
    • 5 (1st + 3rd): Sometimes useful for specific props.
    • 127 (All): Don't do this.

INS_HNTCH_MODE

Default 1
Range 0 4

Harmonic Notch Filter Dynamic Mode (INS_HNTCH_MODE)

Description

INS_HNTCH_MODE tells the filter how to find the noise. Motor noise moves as you change throttle. This parameter selects the "Sensor" used to track that movement.

  • 0: Fixed. The filter sits at INS_HNTCH_FREQ and never moves. Useful for frame resonance that doesn't change.
  • 1: Throttle (Default). Uses the estimated throttle output. If you throttle up, the filter frequency rises. Simple and effective for most drones without RPM sensors.
  • 2: RPM Sensor. Uses real-time data from an RPM sensor. Extremely accurate.
  • 3: ESC Telemetry. Uses RPM data reported by BLHeli_32/AM32 ESCs via DShot. The "Gold Standard" for filtering.
  • 4: Dynamic FFT. Uses a Fast Fourier Transform to "listen" to the noise and find the peak automatically. CPU intensive but requires no external sensors.

The Mathematics

Throttle Mode (1):
$$ f\_{center} = \text{FREQ} \cdot \frac{\text{Throttle}{current} - \text{Throttle}{min}}{\text{REF} - \text{Throttle}{min}} + f{min} $$
(Simplified linear model).

ESC/RPM Mode (2/3):
$$ f\_{center} = \text{RPM}\_{average} / 60 $$

The Engineer's View

This maps to the _tracking_mode member of HarmonicNotchFilterParams.

  • Throttle: Low latency, but an "estimate". Requires tuning INS_HNTCH_REF.
  • ESC Telemetry: High accuracy, but can have transport latency.
  • FFT: High latency (window size dependent), but requires zero tuning of reference values.

Tuning & Behavior

  • Default Value: 1 (Throttle)
  • Recommendation:
    • If you have BLHeli_32/AM32 ESCs, set to 3 (ESC Telemetry).
    • If you have a powerful H7 board (Cube Orange, Durandal), set to 4 (FFT).
    • Otherwise, stick with 1 (Throttle) and tune INS_HNTCH_REF carefully.

INS_HNTCH_OPTS

Default 0
Range 0 31

Harmonic Notch Filter options (INS_HNTCH_OPTS)

Description

INS_HNTCH_OPTS provides advanced tweaks to how the filter operates.

  • Bit 0 (1): Double Notch. Puts two notches side-by-side to create a wider, flatter stopband. Good for broad noise peaks.
  • Bit 1 (2): Multi-Source. Used with FFT or ESC telemetry to track multiple independent peaks (e.g., different motors spinning at different speeds) instead of just one average frequency.
  • Bit 2 (4): Update at loop rate. Updates the filter center frequency every main loop cycle instead of subsampled. Higher CPU usage, better tracking.
  • Bit 3 (8): Enable on All IMUs. Forces the filter to run on all gyros, not just the primary. Crucial for EKF3 affinity/lane switching to work correctly.
  • Bit 4 (16): Triple Notch. Even wider than Double.

The Mathematics

Double Notch: Instead of one filter at $f\_0$, it places two at $f\_0 \pm \delta$, creating a "W" shape (or flat bottom) response.

Multi-Source: Allocates distinct filters for each frequency input source.

The Engineer's View

  • Bit 3 (8) - EnableOnAllIMUs: Highly recommended for redundancy. If the primary gyro fails and EKF switches to the secondary, you want that secondary to be filtered too.
  • Bit 1 (2) - Multi-Source: Essential for Dynamic FFT setups to track individual motor peaks.

Tuning & Behavior

  • Default Value: 0
  • Recommendation:
    • Set Bit 3 (8) -> Value 8. (Filter all IMUs).
    • If using FFT: Set Bit 1 (2) + Bit 4 (16) (Triple Notch) often works well -> Value 2 + 16 = 18 (or 2+8 = 10).
    • If using ESC Telemetry: Set Bit 1 (2) -> Value 2 (Track individual motors).

INS_HNTCH_REF

Default 0
Range 0.0 1.0

Harmonic Notch Filter reference value (INS_HNTCH_REF)

Description

INS_HNTCH_REF tells the filter how to interpret the dynamic sensor data.

  • Throttle Mode (1): This is your Hover Throttle.
    • If you hover at 35% throttle, set this to 0.35.
    • The filter assumes that at 0.35 throttle, the noise is at INS_HNTCH_FREQ.
  • ESC/RPM Mode (2/3): This is a Scaler.
    • Usually set to 1.0 (No scaling).
    • If you have a helicopter where the RPM sensor reports Motor RPM but the noise is at Rotor RPM (gear ratio), you can use this to scale it. Or if using FFT, this is unused.

The Mathematics

Throttle Mode:
$$ \text{Scaling Factor} = \frac{\text{Current Throttle}}{\text{INS\_HNTCH\_REF}} $$
$$ f\_{notch} = \text{INS\_HNTCH\_FREQ} \times \sqrt{\text{Scaling Factor}} $$
(Note: The relationship is often modeled as square root for RPM vs Throttle).

The Engineer's View

If set to 0 in dynamic modes, the filter effectively becomes static or disabled (depending on code path).
In FFT Mode, this parameter is typically ignored, but setting it to a non-zero value is sometimes required to "arm" the dynamic logic in older firmwares.

Tuning & Behavior

  • Default Value: 0
  • Range: 0.0 - 1.0
  • Critical for Throttle Mode: If this is wrong, the notch will move incorrectly. Ideally, perform a "Hover Learn" flight or check MOT_THST_HOVER and copy that value here.

INS_LOG_BAT_CNT

Default 1024
Range 512 16384

Batch Sampler Sample Count (INS_LOG_BAT_CNT)

Description

INS_LOG_BAT_CNT determines the resolution of your FFT graph.

A larger sample count means you can see finer frequency details (e.g., distinguishing between 100Hz and 102Hz). However, larger batches take longer to write to the SD card, potentially causing log gaps.

Tuning & Behavior

  • Default Value: 1024 samples.
  • Recommendation: 1024 is sufficient for most tuning. Use 4096 for precision analysis.

INS_LOG_BAT_LGCT

Default 0
Range 0 1000

Batch Sampler Log Count (INS_LOG_BAT_LGCT)

Description

INS_LOG_BAT_LGCT acts as a limit switch for the data recorder.

Since batch logs are huge, recording them for an entire 30-minute flight would generate gigabytes of data and potentially crash the logger. This parameter stops the sampler after capturing a set number of snapshots.

Tuning & Behavior

  • Default Value: 0 (Unlimited/Disabled?). Wait, usually 0 means disabled?
    • Correction: In modern ArduPilot, 0 usually means "Disabled" for the trigger, or "Unlimited" depending on context. For this parameter, it typically means "Don't stop until disarmed."
  • Recommendation: Set to 0 for general flights. Set to 10 if you only need a quick sample of the hover.

INS_LOG_BAT_LGIN

ms
Default 20
Range 0 10000

Batch Sampler Log Interval (INS_LOG_BAT_LGIN)

Description

INS_LOG_BAT_LGIN controls the "Frame Rate" of the vibration recorder.

It sets the delay between finishing one batch and starting the next.

Tuning & Behavior

  • Default Value: 20 ms.
  • 0: Disabled (or continuous if supported).
  • Recommendation: Keep default. Faster logging uses more SD card bandwidth.

INS_LOG_BAT_MASK

Default 0
Range 0 511

Sensor Bitmask (INS_LOG_BAT_MASK)

Description

INS_LOG_BAT_MASK enables "Batch Sampling". This is a special high-rate logging mode used primarily for FFT (Fast Fourier Transform) Analysis.

When enabled, ArduPilot logs short bursts of high-frequency gyro data (e.g., at 1kHz or 2kHz) to the SD card. This data is critical for identifying motor noise frequencies so you can tune the Harmonic Notch Filters.

  • 0: Disabled (Normal logging).
  • 1: Log IMU 1 Gyro.
  • 3 (1+2): Log IMU 1 & 2 Gyros (Recommended for tuning).

The Mathematics

$$ \text{Active Samplers} = \sum\_{k=0}^{n} (2^k \text{ is set}) \rightarrow \text{Sensor } k $$

  • Bit 0 (1): IMU 1 Gyro
  • Bit 1 (2): IMU 2 Gyro
  • Bit 2 (4): IMU 3 Gyro
  • Bit 3 (8): IMU 1 Accel
  • Bit 4 (16): IMU 2 Accel
  • ...

The Engineer's View

Used in AP_InertialSensor::BatchSampler::init().
Batch sampling creates massive log files. A 5-minute flight with INS_LOG_BAT_MASK = 1 can produce a 100MB+ binary log. The data is stored in ISBH and ISBD messages.

Tuning & Behavior

  • Default Value: 0 (Disabled)
  • Recommendation:
    • For Tuning: Set to 1 (or 3) for a single hover flight to capture noise data.
    • For Normal Flight: Set to 0. Leaving this on wastes SD card space and CPU cycles (though it runs at low priority).
  • How to use:
    1. Set INS_LOG_BAT_MASK = 1.
    2. Set INS_LOG_BAT_OPT = 0 (Pre-filter) to see raw noise.
    3. Fly/Hover.
    4. Download log.
    5. Use Mission Planner's "FFT" button to analyze the noise profile.

INS_LOG_BAT_OPT

Default 0
Range 0 31

Batch Sampling Options (INS_LOG_BAT_OPT)

Description

INS_LOG_BAT_OPT configures the high-speed data recorder for vibration analysis.

To tune the Harmonic Notch Filter, you need to know exactly what frequencies your motors are vibrating at. Standard logs are too slow to capture this. The "Batch Sampler" captures short bursts of high-speed gyro data (1kHz+) and writes them to the log.

  • Bit 0: Sensor Selection. (0 = Gyro, 1 = Accel).
  • Bit 1: Message Type. (0 = Post-Filter, 1 = Pre-Filter).
  • Bit 2: Sample Rate. (0 = 1kHz, 1 = 2kHz+).

Tuning & Behavior

  • Default Value: 0 (Gyro, Post-Filter).
  • Recommendation: Set to 0 for standard Gyro FFT analysis. Set to 2 (Bit 1) to see the "Raw" noise before any filters are applied.

INS_POS

m
Default 0
Range -5 5

IMU Position Offset (INS_POS)

Description

INS_POS (often appearing as INS_POS_X/Y/Z) tells the autopilot exactly where the primary flight controller IMU is mounted relative to the drone's balance point (Center of Gravity).

If the flight controller is mounted far away from the center (e.g., at the front of a long airplane), when the plane pitches, the IMU will experience an "Up/Down" acceleration that isn't actually happening to the whole plane. Correctly setting these offsets allows the EKF to mathematically "move" the IMU back to the center of gravity, resulting in a much cleaner and more accurate position estimate.

Tuning & Behavior

  • Default: 0.
  • Measurement: Measure the distance from the center of the flight controller to the vehicle's CoG.
    • X: Positive = Forward.
    • Y: Positive = Right.
    • Z: Positive = Down.
  • Recommendation: Leave at 0 if the flight controller is within 5-10cm of the center. Accuracy is only critical for high-performance navigation or very large frames.

INS_POS1

m
Default 0 0 0
Range -5 5

IMU 1 Position Offset (INS_POS1)

Description

INS_POS1 defines the physical location of the primary accelerometer.

The EKF assumes the IMU is at the center of the vehicle. If the flight controller is mounted far from the Center of Gravity (CoG), rotation can be misinterpreted as acceleration (centripetal force). This parameter allows the EKF to correct for that lever-arm effect.

Tuning & Behavior

  • Default Value: 0,0,0.
  • Usage: Measure the distance from the CoG to the center of the flight controller in meters.
  • X: Positive Forward.
  • Y: Positive Right.
  • Z: Positive Down.

INS_POS2

null
Default 0.0f
Range null

None

Note: This parameter functions identically to INS_POS1.

INS_POS3

null
Default 0.0f
Range null

None

Note: This parameter functions identically to INS_POS1.

INS_RAW_LOG_OPT

Default 0
Range 0 65535

Raw IMU Logging Options (INS_RAW_LOG_OPT)

Description

INS_RAW_LOG_OPT enables high-speed data recording from the IMUs.

By default, ArduPilot logs filtered IMU data at a reduced rate. This parameter allows you to log the raw, unfiltered sensor data at full speed (up to 4kHz depending on hardware). This is critical for FFT analysis, notch filter tuning, and diagnosing high-frequency vibration issues.

Tuning & Behavior

  • 0: Disabled.
  • 1: Log Primary Gyro/Accel.
  • 2: Log Secondary Gyro/Accel.
  • 4: Log Tertiary Gyro/Accel.
  • 7: Log All IMUs.

Recommendation

Only enable this for short debugging flights. Raw logging consumes significant SD card bandwidth and can fill the logs quickly.

INS_SAMPLE_RATE

kHz
Default 1
Range 1 3

IMU Sample Rate (INS_SAMPLE_RATE)

Description

INS_SAMPLE_RATE defines how fast the flight controller talks to the accelerometer and gyroscope chips.

A higher sample rate allows for better vibration filtering (aliasing prevention) and more responsive flight control. However, it also increases the CPU load on the autopilot.

  • 1: 1 kHz (Standard). Suitable for most F4 and F7 flight controllers.
  • 2: 2 kHz.
  • 3: 8 kHz. Only recommended for high-performance H7 flight controllers and high-end IMUs (like ICM series).

Tuning & Behavior

  • Default: 1 kHz.
  • Recommendation: Only increase this if your CPU load (PM_CPU_Usage) remains low (below 50%) and you are looking for the absolute best flight performance on a racing quad.

INS_STILL_THRESH

$m/s^2$
Default 0.1
Range 0.05 0.5

INS Stillness Threshold (INS_STILL_THRESH)

Description

INS_STILL_THRESH defines "Motionless."

When calibrating gyroscopes or performing pre-arm checks, the autopilot needs to know if the drone is sitting still. If the accelerometer variance is below this threshold, the system is assumed to be stationary.

Tuning & Behavior

  • Default Value: 0.1 $m/s^2$.
  • Increase: If you are on a boat or a swaying platform.
  • Decrease: For laboratory precision calibration.

INS_TCAL1_ACC1

Default 0
Range -10 10

IMU1 Temperature Cal Accel 1 (INS_TCAL1_ACC1)

Description

INS_TCAL1_ACC1 is the linear component of the temperature compensation curve for the first IMU's accelerometer.

As the flight controller heats up (due to the STM32 processor or sunny weather), the accelerometer reading can drift. This parameter corrects that drift based on the difference between the current temperature and the calibration reference temperature (35°C).

The Mathematics

The correction applied to the sensor reading is a 3rd-order polynomial:

$$ \text{Correction} = \left( C\_1 \Delta T + C\_2 \Delta T^2 + C\_3 \Delta T^3 \right) \times 10^{-6} $$

Where:

  • $C\_1$ is INS_TCAL1_ACC1
  • $\Delta T = T\_{current} - 35^\circ C$
  • The factor $10^{-6}$ scales the parameter values (which are stored as large integers for easier GCS editing) back to their physical units.

The Engineer's View

Defined in AP_InertialSensor_tempcal.cpp.
This parameter is learned automatically when you run the "Temperature Calibration" routine. You should generally not edit this manually unless you are manually fitting a curve to logged data.

Tuning & Behavior

  • Default Value: 0.
  • Recommendation: Perform a temperature calibration if you see the EKF attitude drift significantly during the first few minutes of flight (warm-up).

INS_TCAL1_ACC2

Default 0
Range -10 10

IMU1 Temperature Cal Accel 2 (INS_TCAL1_ACC2)

Description

INS_TCAL1_ACC2 is the quadratic component of the temperature compensation curve.

The Mathematics

$$ \text{Correction} = \left( C\_1 \Delta T + C\_2 \Delta T^2 + C\_3 \Delta T^3 \right) \times 10^{-6} $$

Where $C\_2$ is INS_TCAL1_ACC2.

Tuning & Behavior

  • Default Value: 0.
  • Recommendation: Do not edit manually.

INS_TCAL1_ACC3

Default 0
Range -10 10

IMU1 Temperature Cal Accel 3 (INS_TCAL1_ACC3)

Description

INS_TCAL1_ACC3 is the cubic component of the temperature compensation curve.

The Mathematics

$$ \text{Correction} = \left( C\_1 \Delta T + C\_2 \Delta T^2 + C\_3 \Delta T^3 \right) \times 10^{-6} $$

Where $C\_3$ is INS_TCAL1_ACC3.

Tuning & Behavior

  • Default Value: 0.
  • Recommendation: Do not edit manually.

INS_TCAL1_ENABLE

Default 0
Range 0 2

IMU1 Temperature Calibration Enable (INS_TCAL1_ENABLE)

Description

INS_TCAL1_ENABLE turns on the thermal compensation logic.

IMUs drift when they get hot. If you have performed a temperature calibration (heating the flight controller while it is stationary), setting this to 1 will apply the learned corrections.

Tuning & Behavior

  • 0: Disabled.
  • 1: Enabled (Use learned values).
  • 2: Learn Calibration (Start learning process).

INS_TCAL1_GYR1

Default 0
Range -10 10

IMU1 Temperature Cal Gyro 1 (INS_TCAL1_GYR1)

Description

INS_TCAL1_GYR1 is the linear component of the temperature compensation curve for the first IMU's gyroscope.

As the flight controller heats up, the gyro bias drifts. This parameter corrects that drift.

The Mathematics

$$ \text{Correction} = \left( C\_1 \Delta T + C\_2 \Delta T^2 + C\_3 \Delta T^3 \right) \times 10^{-6} $$

Where $C\_1$ is INS_TCAL1_GYR1.

Tuning & Behavior

  • Default Value: 0.
  • Recommendation: Do not edit manually. Perform a temperature calibration.

INS_TCAL1_GYR2

Default 0
Range -10 10

IMU1 Temperature Cal Gyro 2 (INS_TCAL1_GYR2)

Description

INS_TCAL1_GYR2 is the quadratic component of the temperature compensation curve for the gyro.

The Mathematics

$$ \text{Correction} = \left( C\_1 \Delta T + C\_2 \Delta T^2 + C\_3 \Delta T^3 \right) \times 10^{-6} $$

Where $C\_2$ is INS_TCAL1_GYR2.

Tuning & Behavior

  • Default Value: 0.

INS_TCAL1_GYR3

Default 0
Range -10 10

IMU1 Temperature Cal Gyro 3 (INS_TCAL1_GYR3)

Description

INS_TCAL1_GYR3 is the cubic component of the temperature compensation curve for the gyro.

The Mathematics

$$ \text{Correction} = \left( C\_1 \Delta T + C\_2 \Delta T^2 + C\_3 \Delta T^3 \right) \times 10^{-6} $$

Where $C\_3$ is INS_TCAL1_GYR3.

Tuning & Behavior

  • Default Value: 0.

INS_TCAL1_TMAX

degC
Default 0
Range 0 85

IMU1 Temperature Calibration Max (INS_TCAL1_TMAX)

Description

INS_TCAL1_TMAX records the hottest temperature reached during calibration.

If the flight controller gets hotter than this during flight, the EKF will stop using the temperature compensation to avoid extrapolating into unknown territory.

Tuning & Behavior

  • Default Value: 0 (Uncalibrated).
  • Recommendation: Do not edit manually.

INS_TCAL1_TMIN

degC
Default 0
Range -40 85

IMU1 Temperature Calibration Min (INS_TCAL1_TMIN)

Description

INS_TCAL1_TMIN records the coldest temperature from the calibration.

Tuning & Behavior

  • Default Value: 0.

INS_TCAL2_ENABLE

null
Default 0
Range null

Enable pullup after altitude wait

Note: This parameter functions identically to INS_TCAL1_ENABLE.

INS_TCAL2_TMAX

degC
Default 70
Range -70 80

Temperature calibration max

Note: This parameter functions identically to INS_TCAL1_TMAX.

INS_TCAL2_TMIN

degC
Default 0
Range -70 80

Temperature calibration min

Note: This parameter functions identically to INS_TCAL1_TMIN.

INS_TCAL3_ENABLE

null
Default 0
Range null

Enable pullup after altitude wait

Note: This parameter functions identically to INS_TCAL1_ENABLE.

INS_TCAL3_TMAX

degC
Default 70
Range -70 80

Temperature calibration max

Note: This parameter functions identically to INS_TCAL1_TMAX.

INS_TCAL3_TMIN

degC
Default 0
Range -70 80

Temperature calibration min

Note: This parameter functions identically to INS_TCAL1_TMIN.

INS_TCAL_ACC1

Default 0
Range -10 10

Accelerometer 1 Temp Coeff (INS_TCAL_ACC1)

Description

INS_TCAL_ACC1 is a learned calibration value.

During a "Temperature Calibration," the flight controller heats up (either naturally or via BRD_HEAT_TARG) while stationary. It measures how the accelerometer bias shifts with temperature and calculates this slope coefficient to subtract the thermal error in flight.

Tuning & Behavior

  • Default Value: 0 (No compensation).
  • Usage: Automatically populated by the temp calibration routine.

INS_TCAL_ACC2

null
Default 0
Range null

Accelerometer 2nd order temperature coefficient Z axis

Note: This parameter functions identically to INS_TCAL_ACC1.

INS_TCAL_ACC3

null
Default 0
Range null

Accelerometer 3rd order temperature coefficient Z axis

Note: This parameter functions identically to INS_TCAL_ACC1.

INS_TCAL_GYR1

Default 0
Range -10 10

Gyroscope 1 Temp Coeff (INS_TCAL_GYR1)

Description

INS_TCAL_GYR1 is the thermal slope for the gyroscope.

Similar to INS_TCAL_ACC1, this value allows the EKF to predict and remove gyro drift caused by temperature changes, improving attitude estimation accuracy during long flights where the board temperature varies.

Tuning & Behavior

  • Default Value: 0.

INS_TCAL_GYR2

null
Default 0
Range null

Gyroscope 2nd order temperature coefficient Z axis

Note: This parameter functions identically to INS_TCAL_GYR1.

INS_TCAL_GYR3

null
Default 0
Range null

Gyroscope 3rd order temperature coefficient Z axis

Note: This parameter functions identically to INS_TCAL_GYR1.

INS_TCAL_OPTIONS

Default 0
Range 0 3

Temperature Calibration Options (INS_TCAL_OPTIONS)

Description

INS_TCAL_OPTIONS controls how the learned temperature calibration data is stored.

  • Bit 0: Persist Accel Calibration. Saves the accel offset/scale to the bootloader sector (if supported) so it survives a full parameter reset.
  • Bit 1: Persist Temp Calibration. Saves the INS_TCAL parameters to the bootloader sector.

Tuning & Behavior

  • Default Value: 0.

INS_TRIM_OPTION

Default 1
Range 0 2

Accel cal trim option (INS_TRIM_OPTION)

Description

INS_TRIM_OPTION determines how ArduPilot calculates the AHRS Trim (Level Horizon) during the Accelerometer Calibration.

  • 0: Don't adjust trims. The calibration only calculates scaling/offsets for the sensor. The trim (level) remains unchanged.
  • 1: Assume first orientation was level (Default). The vehicle is assumed to be perfectly level when you start the calibration.
  • 2: Assume ACC_BODYFIX is aligned. Assumes the flight controller is perfectly aligned with the frame, and calculating trims is unnecessary.

The Mathematics

The calibration solves for offsets $\vec{b}$ and scale factors $S$.
$$ \vec{a}{cal} = S (\vec{a}{raw} - \vec{b}) $$
Then, it calculates the rotation matrix $R\_{trim}$ required to make the first sample match the gravity vector $\vec{g} = [0, 0, 1]^T$.

The Engineer's View

Used in AP_InertialSensor::_calculate_trim().
If set to 1, the "Level" step is implicitly done as part of the 6-point calibration.
If set to 0, you must run a separate "Calibrate Level" command after the 6-point calibration.

Tuning & Behavior

  • Default Value: 1
  • Recommendation: Leave at 1 for most users. Just ensure the drone is level when you click "Calibrate Accelerometers".

INS_USE

Default 1
Range 0 1

Use first IMU (INS_USE)

Description

INS_USE toggles the first IMU (gyro/accel) for state estimation.

  • 1 (Enabled): The EKF can use this sensor for flight.
  • 0 (Disabled): The sensor is initialized and logged, but the EKF will ignore its data.

The Mathematics

The EKF runs multiple "lanes" (instances). If INS_USE is 0, the lane corresponding to this sensor is flagged as "Not Active" or "Unhealthy" (depending on implementation details in EKF2/EKF3).

The Engineer's View

Used in AP_InertialSensor::use_gyro() and use_accel().
If set to 0, the driver still runs (unlike INS_ENABLE_MASK), but get_gyro_health() effectively returns false for the purpose of fusion.

Tuning & Behavior

  • Default Value: 1
  • Use Case: If IMU 1 is noisy (e.g., resonance on the specific chip), you can set INS_USE = 0 to force the EKF to rely on IMU 2 and 3.

INS_USE2

null
Default 1
Range null

None

Note: This parameter functions identically to INS_USE.

INS_USE3

null
Default 1
Range null

None

Note: This parameter functions identically to INS_USE.