MAVLINKHUD

Overview

The EK2 parameter group configures the Legacy EKF2 state estimator. For many years, this was the default navigation filter for ArduPilot. It fuses data from IMUs, GPS, Barometers, and Compasses to determine Position, Velocity, and Attitude.

Note: As of ArduPilot 4.1+, EKF3 (EK3) is the default. EKF2 is kept for legacy compatibility on F4 boards where EKF3 might be too heavy, or for users who trust its proven track record.

Key Concepts

1. Source Switching (EK2_GPS_TYPE, EK2_ALT_SOURCE)

EKF2 allows selecting primary sources, but it is less flexible than EKF3.

  • GPS Type: 0=GPS 3D Vel, 1=GPS 2D Vel, etc.
  • Alt Source: 0=Baro, 1=Rangefinder, 2=GPS, 3=Beacon.

2. Innovation Gates (_I_GATE)

The filter rejects sensor data that deviates too far from the current estimate.

  • EK2_POS_I_GATE: How many standard deviations a GPS position update can "jump" before being rejected as a glitch.

3. Noise Parameters (_M_NSE, _P_NSE)

Tuning parameters representing the expected noise of the sensors.

  • Increase if your sensors are noisy/vibrating (trusts the sensor less).
  • Decrease if you have high-end sensors (trusts the sensor more).

Parameter Breakdown

  • EK2_ENABLE: Master switch.
  • EK2_IMU_MASK: Selects which IMUs to use (1=IMU1, 2=IMU2, 3=Both).
  • EK2_MAG_CAL: EKF2 can learn magnetometer offsets in flight.

Integration Guide

  • Selection: To use EKF2, set AHRS_EKF_TYPE = 2 and EK2_ENABLE = 1.
  • Tuning: Generally, default parameters work for 99% of vehicles. Modifying noise parameters is only for advanced users with specific vibration issues.

Developer Notes

  • Library: libraries/AP_NavEKF2
  • States: 22-state filter.

EK2_ABIAS_P_NSE

$m/s^3$
Default 5.0E-03
Range 0.00001 0.005

Accelerometer bias stability (EK2_ABIAS_P_NSE)

Description

Controls how quickly the EKF adapts to changes in accelerometer bias.

EK2_ACC_P_NSE

$m/s^2$
Default 0.6
Range 0.01 1.0

Accelerometer noise (EK2_ACC_P_NSE)

Description

Specifies the expected high-frequency noise level in the accelerometers.

EK2_ALT_M_NSE

m
Default 3.0
Range 0.1 10.0

Altitude measurement noise (EK2_ALT_M_NSE)

Description

Specifies the expected noise level in the altitude data (typically Baro). Increasing this value reduces the weighting of altitude measurements, making the filter respond more slowly to altitude changes.

EK2_ALT_SOURCE

Default 0
Range 0 3

Primary altitude sensor source (EK2_ALT_SOURCE)

Description

Selects the primary hardware source for altitude estimation within the EKF2 algorithm.

Tuning & Behavior

  • Default Value: 0 (Baro)
  • Values: 0:Use Baro, 1:Use Range Finder, 2:Use GPS, 3:Use Range Beacon

EK2_BCN_DELAY

ms
Default 50
Range 0 127

Range beacon measurement delay (EK2_BCN_DELAY)

Description

Compensates for processing delay in range-beacon based positioning systems.

EK2_BCN_I_GTE

Default 500
Range 100 1000

Range beacon measurement gate size (EK2_BCN_I_GTE)

Description

Strictness of the range beacon consistency check.

EK2_BCN_M_NSE

m
Default 1.0
Range 0.1 10.0

Range beacon measurement noise (EK2_BCN_M_NSE)

Description

Specifies the expected noise level in the range beacon data.

EK2_CHECK_SCALE

%
Default 100
Range 50 200

GPS accuracy check scaler (EK2_CHECK_SCALE)

Description

Adjusts the global "strictness" of the pre-flight GPS accuracy checks.

EK2_EAS_I_GATE

Default 400
Range 100 1000

Airspeed measurement gate size (EK2_EAS_I_GATE)

Description

Strictness of the airspeed sensor consistency check.

EK2_EAS_M_NSE

m/s
Default 1.4
Range 0.5 5.0

Equivalent airspeed measurement noise (EK2_EAS_M_NSE)

Description

Specifies the expected noise level in the airspeed sensor data.

EK2_ENABLE

Default 0
Range 0 1

Enable EKF2 (EK2_ENABLE)

Description

Global switch to enable the second-generation Extended Kalman Filter. Enabling EKF2 makes the math run in the background, but it is only used for flight control if AHRS_EKF_TYPE is set to 2.

Tuning & Behavior

  • Default Value: 0 (Disabled)
  • Requires reboot after changing.

EK2_FLOW_DELAY

ms
Default 10
Range 0 127

Optical Flow measurement delay (EK2_FLOW_DELAY)

Description

Compensates for the processing delay in the optical flow sensor.

EK2_FLOW_I_GATE

Default 300
Range 100 1000

Optical Flow measurement gate size (EK2_FLOW_I_GATE)

Description

Strictness of the optical flow consistency check.

EK2_FLOW_M_NSE

rad/s
Default 0.25
Range 0.05 1.0

Optical flow measurement noise (EK2_FLOW_M_NSE)

Description

Specifies the expected noise level in the optical flow data.

EK2_FLOW_USE

Default 1
Range 0 2

Optical flow use bitmask (EK2_FLOW_USE)

Description

Determines how optical flow sensor data is utilized.

  • 1: Navigation (Velocity estimation)
  • 2: Terrain (Height estimation)

EK2_GBIAS_P_NSE

$rad/s^2$
Default 1.0E-04
Range 0.00001 0.001

Rate gyro bias stability (EK2_GBIAS_P_NSE)

Description

Controls how quickly the EKF adapts to changes in gyro bias (drift). Higher values allow for faster adaptation but result in noisier bias estimates.

EK2_GLITCH_RAD

m
Default 25
Range 10 100

GPS glitch radius gate size (EK2_GLITCH_RAD)

Description

Defines the maximum allowed distance "jump" in GPS position before the EKF flags it as a glitch.

EK2_GPS_CHECK

null
Default ARMING_CHECK_ALL
Range null

Arm Checks to Perform (bitmask)

Note: This parameter functions identically to EK3_GPS_CHECK for EKF2.

EK2_GPS_TYPE

Default 0
Range 0 3

GPS mode control (EK2_GPS_TYPE)

Description

Determines how the EKF incorporates GPS data (velocity and position) into its estimation.

Tuning & Behavior

  • Default Value: 0 (GPS 3D Vel and 2D Pos)
  • Values: 0:GPS 3D Vel and 2D Pos, 1:GPS 2D vel and 2D pos, 2:GPS 2D pos, 3:No GPS
  • Option 3 is useful for indoor flight with optical flow.

EK2_GSCL_P_NSE

Hz
Default 0.00001
Range 0.000001 0.001

EKF2 Gyro Scale Factor Process Noise (EK2_GSCL_P_NSE)

Description

EK2_GSCL_P_NSE determines how fast the EKF2 learns the scale factor errors of the gyroscopes.

Gyroscopes are not perfectly linear; they might report 101 degrees/sec when the drone actually rotated 100 degrees. This parameter allows the EKF to identify and correct that "Scale Error" over time.

Tuning & Behavior

  • Default Value: 0.00001 Hz.
  • Higher Value: Faster learning, but heading might become unstable during aggressive maneuvers.
  • Lower Value: Slower, more stable learning.

EK2_GSF_RST_MAX

Default 2
Range 1 10

Maximum resets to the EKF-GSF yaw estimate allowed (EK2_GSF_RST_MAX)

Description

Limits the number of times the EKF can "jump" its heading based on the GSF estimate to prevent repeated resets in difficult magnetic environments.

EK2_GSF_RUN_MASK

Default 3

Bitmask of which EKF-GSF yaw estimators run (EK2_GSF_RUN_MASK)

Description

Enables the Gaussian Sum Filter (GSF) yaw estimator for specific EKF cores. GSF provides a yaw estimate that doesn't rely on the magnetometer.

EK2_GSF_USE_MASK

Default 3

Bitmask of which EKF-GSF yaw estimators are used (EK2_GSF_USE_MASK)

Description

Determines which EKF cores are permitted to use the GSF yaw estimate for emergency recovery or as a primary source.

EK2_GYRO_P_NSE

rad/s
Default 3.0E-02
Range 0.0001 0.1

Rate gyro noise (EK2_GYRO_P_NSE)

Description

Specifies the expected high-frequency noise level in the gyroscopes. Higher values make the EKF trust the gyros less and rely more on other sensors (like compass and GPS).

EK2_HGT_DELAY

ms
Default 60
Range 0 250

Height measurement delay (EK2_HGT_DELAY)

Description

Compensates for the processing and transmission time delay inherent in the altitude sensor (usually the barometer).

EK2_HGT_I_GATE

Default 500
Range 100 1000

Height measurement gate size (EK2_HGT_I_GATE)

Description

Determines the strictness of the altitude check.

EK2_HRT_FILT

Hz
Default 2.0
Range 0.1 30.0

Height rate filter crossover frequency (EK2_HRT_FILT)

Description

Tuning for the vertical velocity (climb/sink rate) estimation.

EK2_IMU_MASK

Default 3

Bitmask of active IMUs (EK2_IMU_MASK)

Description

Defines which physical IMUs (Accelerometers/Gyros) will have an associated EKF2 core instance.

EK2_MAGB_P_NSE

Gauss/s
Default 0.001
Range 0.00001 0.01

Body magnetic field process noise (EK2_MAGB_P_NSE)

Description

Specifies how quickly the EKF adapts its estimate of the aircraft's internal magnetic interference (bias).

EK2_MAGE_P_NSE

Gauss/s
Default 0.001
Range 0.00001 0.01

Earth magnetic field process noise (EK2_MAGE_P_NSE)

Description

Specifies how quickly the EKF adapts its estimate of the local Earth magnetic field.

EK2_MAG_CAL

Default 3
Range 0 4

Magnetometer default fusion mode (EK2_MAG_CAL)

Description

Configures the EKF's magnetometer processing logic.

Tuning & Behavior

  • Default Value: 3 (After first climb yaw reset) for Copter, 0 (When flying) for Plane
  • Values: 0:When flying, 1:When manoeuvring, 2:Never, 3:After first climb yaw reset, 4:Always
  • Settings 0, 1, and 3 are standard for most aircraft.

EK2_MAG_EF_LIM

mGauss
Default 50
Range 0 500

EarthField error limit (EK2_MAG_EF_LIM)

Description

Sanity check between the EKF's learned magnetic field and the mathematical World Magnetic Model (WMM).

EK2_MAG_I_GATE

Default 300
Range 100 1000

Magnetometer measurement gate size (EK2_MAG_I_GATE)

Description

Determines the strictness of the magnetometer check.

EK2_MAG_MASK

Default 0

Bitmask of cores using heading fusion (EK2_MAG_MASK)

Description

Allows specific EKF cores to be forced into a simpler (and sometimes more robust) magnetic heading fusion mode.

EK2_MAG_M_NSE

Gauss
Default 0.05
Range 0.01 0.5

Magnetometer measurement noise (EK2_MAG_M_NSE)

Description

Specifies the expected noise level in the magnetometer data. Increasing it reduces the weighting of the compass in heading estimation.

EK2_MAX_FLOW

rad/s
Default 2.5
Range 1.0 4.0

Maximum valid optical flow rate (EK2_MAX_FLOW)

Description

Upper bound for valid optical flow readings. Readings above this rate are ignored as being potentially corrupted by motion blur or sensor limits.

EK2_NOAID_M_NSE

m
Default 10.0
Range 0.5 50.0

Non-GPS position uncertainty (EK2_NOAID_M_NSE)

Description

Specifies how much "drift" is allowed when the aircraft is flying without a position source (dead-reckoning).

EK2_OGN_HGT_MASK

Default 0

EKF reference height correction bitmask (EK2_OGN_HGT_MASK)

Description

Configuration for correcting barometric drift using GPS altitude data.

EK2_OPTIONS

Default 0

Optional EKF behaviour (EK2_OPTIONS)

Description

Configuration bitmask for advanced EKF behaviors.

  • Bit 0: DisableExternalNavigation

EK2_POSNE_M_NSE

m
Default 1.0
Range 0.1 10.0

GPS horizontal position noise (EK2_POSNE_M_NSE)

Description

Specifies the expected noise level in the GPS horizontal position data.

EK2_POS_I_GATE

Default 500
Range 100 1000

GPS position measurement gate size (EK2_POS_I_GATE)

Description

Determines the strictness of the GPS position check.

EK2_RNG_I_GATE

Default 500
Range 100 1000

Range finder measurement gate size (EK2_RNG_I_GATE)

Description

Strictness of the rangefinder consistency check.

EK2_RNG_M_NSE

m
Default 0.5
Range 0.1 10.0

Range finder measurement noise (EK2_RNG_M_NSE)

Description

Specifies the expected noise level in the rangefinder data.

EK2_RNG_USE_HGT

%
Default -1
Range -1 70

Range finder switch height percentage (EK2_RNG_USE_HGT)

Description

Threshold for automatically switching to the rangefinder as the primary altitude source when flying close to the ground.

  • -1 disables this feature.

EK2_RNG_USE_SPD

m/s
Default 2.0
Range 2.0 6.0

Range finder max ground speed (EK2_RNG_USE_SPD)

Description

Safety limit that disables rangefinder-based altitude estimation at high speeds, where tilt and terrain variations can introduce significant errors.

EK2_TAU_OUTPUT

cs
Default 25
Range 10 50

Output complementary filter time constant (EK2_TAU_OUTPUT)

Description

Determines the responsiveness of the final estimated output.

EK2_TERR_GRAD

Default 0.1
Range 0 0.2

Maximum terrain gradient (EK2_TERR_GRAD)

Description

Assumption about the maximum steepness of the ground, used for terrain height estimation.

EK2_VELD_M_NSE

m/s
Default 0.5
Range 0.05 5.0

GPS vertical velocity noise (EK2_VELD_M_NSE)

Description

Specifies the expected noise level in the GPS vertical velocity (climb/sink) data.

EK2_VELNE_M_NSE

m/s
Default 0.5
Range 0.05 5.0

GPS horizontal velocity noise (EK2_VELNE_M_NSE)

Description

Specifies the expected noise level in the GPS horizontal velocity data. Increasing this value reduces the weighting of GPS velocity measurements in the EKF.

Tuning & Behavior

  • Default Value: 0.5 m/s (Plane/Rover), 0.3 m/s (Copter)
  • Range: 0.05 to 5.0 m/s

EK2_VEL_I_GATE

Default 500
Range 100 1000

GPS velocity innovation gate size (EK2_VEL_I_GATE)

Description

Determines the "strictness" of the GPS velocity check. Decreasing it makes the EKF more likely to reject GPS data that seems slightly inconsistent with other sensors. Increasing it makes the EKF more tolerant but risks accepting bad GPS data.

EK2_WIND_PSCALE

Default 0.5
Range 0.0 1.0

Height rate to wind process noise scaler (EK2_WIND_PSCALE)

Description

Accounts for the fact that wind speed and direction typically change more rapidly with altitude.

EK2_WIND_P_NSE

$m/s^2$
Default 0.1
Range 0.01 1.0

Wind velocity process noise (EK2_WIND_P_NSE)

Description

Controls how quickly the EKF adapts to changing wind conditions.

EK2_YAW_I_GATE

Default 300
Range 100 1000

Yaw measurement gate size (EK2_YAW_I_GATE)

Description

Determines the strictness of the heading (yaw) check.

EK2_YAW_M_NSE

rad
Default 0.5
Range 0.05 1.0

Yaw measurement noise (EK2_YAW_M_NSE)

Description

Specifies the expected noise level in the yaw (heading) data.