MAVLINKHUD

Overview

The EK3 parameter group configures the Modern EKF3 state estimator. This is the default and recommended navigation filter for all modern ArduPilot vehicles.

EKF3 differs from EKF2 by offering Source Switching ("Lane Switching"). It can seamlessly transition between different navigation sources in flight (e.g., GPS outdoors -> Optical Flow indoors -> Beacon) based on pilot switches or signal health.

Key Concepts

1. Source Switching (EK3_SRCn_...)

You can define up to 3 sets of sensor configurations ("Sources").

  • EK3_SRC1_POSXY: Horizontal Position Source (GPS, Flow, Beacon, None).
  • EK3_SRC1_VELXY: Horizontal Velocity Source.
  • EK3_SRC1_POSZ: Vertical Position Source (Baro, Rangefinder, GPS).
  • EK3_SRC1_YAW: Heading Source (Compass, GPS Moving Baseline, External).

The pilot can switch between SRC1, SRC2, and SRC3 using an RC channel (RCx_OPTION = 90).

2. Multi-Core Affinity (EK3_AFFINITY)

On H7 processors, EKF3 can run multiple "Lanes" (Instances) on different IMUs simultaneously. EK3_AFFINITY controls which IMU is assigned to which EKF lane to maximize redundancy.

3. Visual Odometry / GPS Denied

EKF3 is the engine that makes non-GPS flight possible.

  • Optical Flow: EK3_SRCx_POSXY = 0, VELXY = 5 (Optical Flow).
  • Visual Odometry: EK3_SRCx_POSXY = 6 (External Nav).

Parameter Breakdown

  • EK3_ENABLE: Master switch.
  • EK3_PRIMARY: Which lane is currently driving the vehicle (Read-only status mostly).
  • EK3_MAG_CAL: In-flight mag calibration options.
  • EK3_FLOW_DELAY: Time lag for optical flow sensor.

Integration Guide

Setting up GPS + Optical Flow Backup

  1. Source 1 (GPS): EK3_SRC1_POSXY = 3 (GPS), VELXY = 3 (GPS), POSZ = 1 (Baro).
  2. Source 2 (Flow): EK3_SRC2_POSXY = 0 (None), VELXY = 5 (OptFlow), POSZ = 2 (Rangefinder).
  3. Switching: Assign RC6 to EKF Pos Source.
    • Low PWM = Source 1 (GPS).
    • Mid PWM = Source 2 (Flow).

Developer Notes

  • Library: libraries/AP_NavEKF3
  • States: 24-state filter.
  • Complexity: EKF3 is significantly more complex to tune than EKF2 but offers far greater capability.

EK3_ABIAS_P_NSE

$m/s^3$
Default 0.002
Range 0.0001 0.01

EKF3 Accelerometer Bias Process Noise (EK3_ABIAS_P_NSE)

Description

EK3_ABIAS_P_NSE tells the EKF how fast it should expect the accelerometer's "zero point" (bias) to drift over time.

Accelerometers drift due to temperature changes and internal stress. The EKF constantly estimates this bias to subtract it.

  • Higher Value: The EKF expects the bias to change rapidly. It will adapt quickly to temperature shifts but might be less stable.
  • Lower Value: The EKF expects a very stable sensor. It will lock onto a bias value and resist changing it.

The Engineer's View

Sets the process noise covariance ($Q$) for the accelerometer bias states ($Z$ axis and $X/Y$ axes).
This essentially sets the "bandwidth" of the bias estimation loop.

Tuning & Behavior

  • Default Value: 0.002
  • Recommendation: Leave at default unless you are seeing "Z-Accel Bias" warnings on a high-quality IMU, in which case you might lower it slightly.

EK3_ACC_BIAS_LIM

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

EKF3 Accelerometer Bias Limit (EK3_ACC_BIAS_LIM)

Description

EK3_ACC_BIAS_LIM is a safety "Sanity Check" for your IMU.

Accelerometers are not perfect; they often have a small constant error (bias). The EKF tries to "Learn" and subtract this error during flight. However, if the IMU is failing or vibrating excessively, the learned bias might become huge and incorrect. This parameter limits how much bias the EKF is allowed to compensate for. If the limit is reached, the EKF will stop trusting that IMU.

The Mathematics

The EKF state vector includes a bias term $b\_{acc}$. This parameter enforces a hard constraint:

$$ |b\_{acc}| \le \text{EK3\_ACC\_BIAS\_LIM} $$

If the filter's internal estimate exceeds this value, it indicates a hardware issue or a significant environmental disturbance.

Tuning & Behavior

  • Default Value: 1.0 $m/s^2$.
  • High Vibration: On very noisy gas-powered helicopters, you might need to increase this to 1.5 to prevent premature EKF lane switching.
  • Health Warning: If your logs show the bias consistently hitting this limit, your flight controller likely has a physical mounting issue or a dying sensor.

EK3_ACC_P_NSE

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

Accelerometer noise (EK3_ACC_P_NSE)

Description

Specifies the expected noise level in the accelerometers for EKF3.

EK3_AFFINITY

Default 0

EKF3 Sensor Affinity Options (EK3_AFFINITY)

Description

Advanced configuration to "lock" specific sensors (e.g., GPS2 or Baro3) to specific EKF cores. This allows the system to evaluate independent combinations of hardware sensors.

Tuning & Behavior

  • Default Value: 0
  • Bitmask:
    • Bit 0: EnableGPSAffinity
    • Bit 1: EnableBaroAffinity
    • Bit 2: EnableCompassAffinity
    • Bit 3: EnableAirspeedAffinity

EK3_ALT_M_NSE

m
Default 2.0
Range 0.1 100.0

Altitude measurement noise (EK3_ALT_M_NSE)

Description

Specifies the expected noise level in the altitude data (Baro/GPS).

EK3_BCN_DELAY

ms
Default 50
Range 0 500

EKF3 Beacon Delay (EK3_BCN_DELAY)

Description

EK3_BCN_DELAY compensates for the time it takes for a Range Beacon (like Pozyx) or Optical Flow sensor to process data and send it to the flight controller.

The EKF uses a "Time Horizon" to rewind history and fuse this delayed data with the correct IMU timestamp.

Tuning & Behavior

  • Default Value: 50 ms.
  • Recommendation: Check your beacon system's datasheet. Incorrect delay causes "toilet bowling" (spiraling) when stopping or changing direction.

EK3_BCN_I_GTE

%
Default 500
Range 100 1000

EKF3 Beacon Innovation Gate (EK3_BCN_I_GTE)

Description

EK3_BCN_I_GTE controls the strictness of the "Glitch Filter" for indoor positioning beacons (like Pozyx or Marvelmind).

When the EKF receives a distance measurement from a beacon, it compares it to where it thinks the drone is. If the difference (Innovation) is too large, the EKF assumes the measurement is a "multipath" reflection or error and rejects it.

  • Low Value (e.g. 300): Strict. Rejects noisy data easily. Good for high-precision flight in clean environments.
  • High Value (e.g. 800): Relaxed. Accepts jumpy data. Use if your beacons are noisy but you trust them more than the IMU.

The Mathematics

The gate check uses the Normalized Innovation Squared (NIS):
$$ \frac{(z\_{meas} - z\_{pred})^2}{S} < \left(\frac{\text{GATE}}{100}\right)^2 $$

Where:

  • $z$ is the range measurement.
  • $S$ is the innovation covariance (expected uncertainty).
  • 500 represents 5 Standard Deviations ($\sigma$).

The Engineer's View

Defined in AP_NavEKF3.
This parameter only applies when EK3_SRC1_POSXY is set to Beacon (4).
Unlike GPS gating (which has separate velocity and position gates), beacon gating is applied to the raw range measurement from each anchor.

Tuning & Behavior

  • Default Value: 500 (5-Sigma).
  • Recommendation:
    • Standard Indoor: Keep at 500.
    • Metal Building (Reflections): Decrease to 300 to reject multipath spikes.
    • Fast Flight: Increase to 800 if the drone moves faster than the beacons can update, causing false rejections due to lag.

EK3_BCN_M_NSE

m
Default 1.0
Range 0.1 10.0

EKF3 Beacon Measurement Noise (EK3_BCN_M_NSE)

Description

EK3_BCN_M_NSE tells the EKF how much to "Trust" your indoor positioning beacons (like Pozyx or Marvelmind).

If your beacons have a lot of multi-path interference (echoes off walls), you should increase this value to prevent the drone from twitching. If they are very precise, you can decrease it to get a tighter position hold.

Tuning & Behavior

  • Default Value: 1.0 m.
  • High Precision: Set to 0.5 if your beacon system consistently reports accuracy better than 10cm.
  • Noisy Environment: Set to 2.0 if you see the drone jumping around in tight indoor spaces.

EK3_BETA_MASK

Default 0

Bitmask controlling sideslip angle fusion (EK3_BETA_MASK)

Description

Enables the "synthetic sideslip" assumption, which assumes that fixed-wing aircraft generally fly with zero sideslip. This allows the EKF to better estimate heading and wind even without a compass or during sensor failures.

Tuning & Behavior

  • Default Value: 0
  • Bitmask:
    • Bit 0: Always (Force fusion even if a yaw sensor is available)
    • Bit 1: WhenNoYawSensor (Only use if magnetometer/GPS-Yaw fails)

EK3_CHECK_SCALE

%
Default 100
Range 50 200

EKF3 Consistency Check Scale (EK3_CHECK_SCALE)

Description

EK3_CHECK_SCALE is the "Sensitivity Knob" for the EKF failsafe system.

It scales the thresholds used to determine if the IMUs, Compass, and GPS are healthy. If you have a very high-vibration airframe that constantly triggers false "EKF Variance" warnings, you can increase this to make the autopilot more "Relaxed."

Tuning & Behavior

  • Default Value: 100 (100%).
  • Increased (e.g., 150): Autopilot becomes more tolerant of noise and small sensor errors. Safer for noisy airframes but slower to detect actual sensor failures.
  • Decreased (e.g., 80): Autopilot becomes "Paranoid." It will detect failures faster but is more likely to trigger false failsafes in gusty wind.

EK3_DRAG_BCOEF_X

kg/m^2
Default 0.0
Range 0.0 1000.0

Ballistic coefficient for X axis drag (EK3_DRAG_BCOEF_X)

Description

A physical parameter representing the aerodynamic drag of the aircraft's body in the forward/backward direction. When set, it allows the EKF to estimate wind velocity based on the tilt required to maintain position.

  • Set to > 0 to enable wind estimation for multirotors.

EK3_DRAG_BCOEF_Y

kg/m²
Default 0.0
Range 0.0 1000.0

EKF3 Lateral Drag Coefficient (EK3_DRAG_BCOEF_Y)

Description

EK3_DRAG_BCOEF_Y is the "Side-Wind Profile" for your drone. It tells the flight controller how much the wind pushes on the side of the drone when it is flying sideways or in a crosswind.

Most drones have a different profile from the side than they do from the front. For example, a drone with a wide battery or long arms will catch more wind from the side. EK3_DRAG_BCOEF_Y allows the EKF3 to accurately calculate the lateral (sideways) component of the wind vector.

  • Set to 0 (Default): Sideways wind estimation is disabled.
  • Set > 1.0: Enables lateral wind estimation.

The Mathematics

The EKF uses the quadratic drag model for the lateral axis ($y$):

$$ a\_{y} = \frac{1}{\text{BCOEF\_Y}} \cdot V\_{rel\_y} \cdot |V\_{rel\_y}| $$

Where:

  • $V\_{rel\_y} = V\_{ground\_y} - V\_{wind\_y}$.
  • $\text{BCOEF\_Y}$ is the value of EK3_DRAG_BCOEF_Y.

Note on Symmetry: On a perfectly square quadcopter, BCOEF_Y should be identical to BCOEF_X. On rectangular drones (longitudinal frames), BCOEF_Y is usually lower than BCOEF_X because the side of the drone has more surface area (more drag).

The Engineer's View

This parameter is the _ballisticCoef_y member in NavEKF3.

To calculate it manually:

  1. Fly the drone sideways at a steady 5-10 m/s on a calm day.
  2. Record the average roll angle ($\phi$).
  3. Calculate lateral acceleration from tilt: $a\_{tilt} = g \cdot \tan(\phi)$.
  4. $\text{BCOEF\_Y} = \frac{V^2}{a\_{tilt}}$.

Tuning & Behavior

  • Default Value: 0.0 (Disabled)
  • Range: 0.0 - 1000.0 kg/m²
  • Effect of Increasing: The EKF assumes the side of the drone is "slippery." It will calculate a higher side-wind speed for a given roll angle.
  • Effect of Decreasing: The EKF assumes the side of the drone is "blunt." It will calculate a lower side-wind speed for a given roll angle.

Use Case Recommendations

  • Dead-Cat / Long-Range Frames: Set to 75% of BCOEF_X. These frames have very long side profiles and catch significant crosswinds.
  • Standard Quad: Set to match BCOEF_X.
  • Drones with Large Side Panels (Advertising/Industrial): Decrease to 10.0. Large surface areas create massive lateral drag.

Troubleshooting

  • Scenario: During a crosswind, the drone's position drifts sideways, and the GCS doesn't show any lateral wind.
    • Diagnosis: EK3_DRAG_BCOEF_Y is set to 0.
    • Fix: Set EK3_DRAG_BCOEF_Y to match your BCOEF_X value.

EK3_DRAG_MCOEF

1/s
Default 0.0
Range 0.0 1.0

Momentum coefficient for propeller drag (EK3_DRAG_MCOEF)

Description

Accounts for the "rotor drag" effect where air velocity normal to the rotor disc is lost, creating a force. This is distinct from body drag and is essential for accurate wind estimation on multicopters.

EK3_DRAG_M_NSE

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

EKF3 Drag Observation Noise (EK3_DRAG_M_NSE)

Description

EK3_DRAG_M_NSE is the key to ArduPilot's Internal Wind Vane.

When a multirotor flies forward (or hovers in a headwind), it must lean. The drone's "face" (frontal area) catches the wind, creating drag. The EKF3 can reverse-calculate the wind speed by looking at how far the drone has to lean to stay stationary. This is called Drag Fusion.

EK3_DRAG_M_NSE defines how much the EKF trusts its "Calculated Drag" vs. other sensors.

  • Low Value: The EKF trusts its drag model implicitly. It will calculate wind speed very quickly and aggressively.
  • High Value: The EKF is cautious. It assumes the drag calculation is noisy (e.g., due to gusts or frame vibrations) and will take longer to update its wind estimate.

The Mathematics

The EKF uses a simplified drag equation to predict the acceleration ($a\_{drag}$) caused by the relative wind ($V\_{rel}$):

$$ a\_{drag} = \text{BCOEF} \cdot |V\_{rel}|^2 + \text{MCOEF} \cdot V\_{rel} $$

EK3_DRAG_M_NSE represents the standard deviation ($\sigma$) of this observation. In the filter, it is squared to form the measurement covariance $R$:

$$ R\_{drag} = (\text{EK3\_DRAG\_M\_NSE})^2 $$

By minimizing the error between this predicted drag and the actual IMU-measured acceleration, the EKF can "solve" for the unknown wind vector.

The Engineer's View

This parameter is the _dragObsNoise member in NavEKF3.

It is inactive unless you have provided your drone's specific drag coefficients (EK3_DRAG_BCOEF_X/Y). Once enabled, the EKF3 core fuses the drag data every 100ms. This provides a "synthetic airspeed" estimate, which is incredibly useful for:

  1. Maintaining ground speed during mapping.
  2. Switching to "Dead Reckoning" more accurately if GPS is lost.
// AP_NavEKF3_Control.cpp
// Wind estimation logic incorporates _dragObsNoise to weight the accelerometer-derived drag observations.

Tuning & Behavior

  • Default Value: 0.5 m/s²
  • Range: 0.1 - 2.0 m/s²
  • Effect of Increasing: Smoother, slower wind estimates. Less susceptible to vibration noise.
  • Effect of Decreasing: Rapid, real-time wind tracking. Better for drones operating in highly gusty environments.

Use Case Recommendations

  • Professional Mapping Drone: Keep at 0.5. Provides a reliable average wind speed for georeferencing.
  • Precision Spraying / Ag-Drones: Decrease to 0.3. These drones must react instantly to wind shifts to prevent chemical drift; a faster wind estimate improves the ground-track accuracy.
  • Racing / High Vibration frames: Increase to 1.0. High vibrations can "confuse" the drag model; a higher noise value prevents the EKF from making erratic wind corrections.

Troubleshooting

  • Scenario: GCS reports wildly varying wind speeds (e.g. jumping from 5 to 20 knots) while hovering in a steady breeze.
    • Diagnosis: EK3_DRAG_M_NSE is too low, or your BCOEF parameters are incorrect.
    • Fix: Increase EK3_DRAG_M_NSE to 0.8.

EK3_EAS_I_GATE

%
Default 400
Range 100 1000

EKF3 Airspeed Innovation Gate (EK3_EAS_I_GATE)

Description

EK3_EAS_I_GATE prevents the EKF from trusting bad airspeed data.

Pitot tubes can get clogged with rain or bugs. If the airspeed sensor reports a value that disagrees wildly with the GPS and IMU (e.g., claiming 100m/s when the GPS says 0), this gate rejects the reading to prevent the plane from stalling or diving.

Tuning & Behavior

  • Default Value: 400 (4 Sigma).
  • Recommendation: Set to 300 for better protection against bad sensors.

EK3_EAS_M_NSE

m/s
Default 1.4
Range 0.5 5.0

EKF3 Airspeed Measurement Noise (EK3_EAS_M_NSE)

Description

EK3_EAS_M_NSE defines how "Clean" the airspeed signal is.

  • 1.4 (Default): Standard for analog pitot tubes.
  • Lower Value: Trusts the airspeed sensor more. Use for high-quality digital sensors (MS4525).
  • Higher Value: Trusts the IMU/GPS more. Use for noisy sensors or turbulent conditions.

Tuning & Behavior

  • Default Value: 1.4 m/s.

EK3_ENABLE

Default 1
Range 0 1

Enable EKF3 (EK3_ENABLE)

Description

Global switch to enable the third-generation Extended Kalman Filter. ArduPilot defaults to EKF3 for most modern hardware. Enabling it makes the math run; set AHRS_EKF_TYPE to 3 to use it for flight control.

Tuning & Behavior

  • Default Value: 1 (Enabled)
  • Requires reboot after changing.

EK3_ERR_THRESH

Default 0.2
Range 0.05 1

EKF3 Lane Relative Error Sensitivity Threshold (EK3_ERR_THRESH)

Description

Tuning for the multi-lane EKF logic. If a standby EKF lane is performing better than the primary by more than this threshold, the flight controller may switch to the healthier lane.

EK3_FLOW_DELAY

ms
Default 10
Range 0 500

EKF3 Optical Flow Delay (EK3_FLOW_DELAY)

Description

EK3_FLOW_DELAY accounts for the processing lag in your Optical Flow camera (e.g., HereFlow, CX-OF).

Flow sensors calculate motion by comparing image frames, which takes time. If this delay isn't accounted for, the EKF will think the motion happened now instead of 10ms ago, causing instability.

Tuning & Behavior

  • Default Value: 10 ms.
  • Recommendation:
    • HereFlow: 10-20 ms.
    • PX4Flow: 10 ms.

EK3_FLOW_I_GATE

%
Default 300
Range 100 1000

EKF3 Flow Innovation Gate (EK3_FLOW_I_GATE)

Description

EK3_FLOW_I_GATE prevents the drone from chasing shadows.

Optical flow sensors can get confused by moving objects or sudden light changes. If the flow sensor reports a movement that is physically impossible given the drone's IMU data, this gate rejects it.

Tuning & Behavior

  • Default Value: 300 (3 Sigma).
  • Recommendation: Set to 500 if you fly over high-contrast terrain (like grass/concrete boundaries) that triggers false rejections.

EK3_FLOW_MAX

rad/s
Default 2.5
Range 0.5 5.0

EKF3 Optical Flow Max Rate (EK3_FLOW_MAX)

Description

EK3_FLOW_MAX filters out bad data from the flow sensor.

Optical flow sensors often glitch when the image moves too fast (motion blur). This parameter tells the EKF to ignore any readings where the flow rate exceeds this limit.

Tuning & Behavior

  • Default Value: 2.5 $rad/s$.
  • Recommendation: Match this to the physical limits of your flow sensor (e.g. CX-OF or HereFlow).

EK3_FLOW_M_NSE

rad/s
Default 0.15
Range 0.05 0.5

EKF3 Optical Flow Measurement Noise (EK3_FLOW_M_NSE)

Description

EK3_FLOW_M_NSE tells the EKF how "Trustworthy" the flow sensor is.

  • Low Value: Trust the flow sensor more. Tighter position hold, but risk of "Toilet Bowling" if the lens is dirty.
  • High Value: Trust the IMU more. Smoother flight, but more drift.

Tuning & Behavior

  • Default Value: 0.15 $rad/s$.

EK3_FLOW_USE

Default 0
Range 0 2

EKF3 Optical Flow Usage (EK3_FLOW_USE)

Description

EK3_FLOW_USE tells the flight controller what to do with the "eyes" of the drone—the Optical Flow sensor.

Optical Flow sensors (like the PX4Flow or HereFlow) look at the ground and track how fast the pixels move. This data can be used to stabilize the drone's position, but only if the EKF knows how to interpret it. This parameter enables the fusion of that visual data into the drone's navigation math.

  • 0 (None): The drone ignores the flow sensor.
  • 1 (Only for Terrain): The drone uses the flow data specifically to help estimate the distance to the ground (useful for landing on varying textures).
  • 2 (For Navigation): The drone uses the flow data as its primary source of speed (velocity). This is the setting used for GPS-Denied flight (indoor flight).

The Mathematics

When set to 2 (Navigation), the EKF uses the flow rate ($\omega\_{flow}$) and height ($h$) to calculate ground velocity ($V\_g$):

$$ V\_g = \text{Filter}(\omega\_{flow} - \omega\_{gyro}) \cdot h $$

Where:

  • $\omega\_{gyro}$ is the drone's own rotation (subtracted to ensure the drone doesn't think it is "moving" just because it tilted).
  • $h$ is the altitude from a Rangefinder.

Constraint: Optical Flow requires a functioning Rangefinder. If EK3_SRC1_POSZ is not set to 2 (Rangefinder) or if the rangefinder fails, Optical Flow navigation will stop working.

The Engineer's View

This parameter is the _flowUse member in NavEKF3.

It is a prerequisite for fusing flow data in AP_NavEKF3_OptFlowFusion.cpp:

// AP_NavEKF3_OptFlowFusion.cpp
const bool fuse_optflow = (frontend->_flowUse == FLOW_USE_NAV) && frontend->sources.useVelXYSource(AP_NavEKF_Source::SourceXY::OPTFLOW);

Note that in modern ArduPilot (4.1+), you must also set the source selection in EK3_SRCn_VELXY to OpticalFlow for this parameter to have full effect.

Tuning & Behavior

  • Default Value: 0 (Disabled)
  • Range: 0 - 2
  • Effect of Enabling (2): The drone will be able to hover in one spot indoors without GPS.
  • Effect of Disabling: The drone will drift indoors and require manual correction by the pilot.

Use Case Recommendations

  • Indoor Warehouse Robotics: Set to 2. Allows the drone to navigate autonomous paths between shelves using only floor texture.
  • Outdoor GPS Fallback: Set to 2. If GPS is lost near a building, the drone can "fail over" to Optical Flow to stay stationary rather than drifting into the building.
  • Precision Landing: Set to 1. Helps the EKF refine its local height estimate relative to the landing pad texture.

Troubleshooting

  • Scenario: Drone starts "orbiting" (circles) as soon as I switch to Loiter indoors with Optical Flow.
    • Diagnosis: Gyro-compensation mismatch. The EKF isn't correctly subtracting the drone's tilt from the flow data.
    • Fix: Ensure FLOW_ORIENT_YAW is correct and perform the "Flow Calibration" flight.

EK3_GBIAS_P_NSE

$rad/s^2$
Default 0.0001
Range 0.00001 0.001

EKF3 Gyroscope Bias Process Noise (EK3_GBIAS_P_NSE)

Description

EK3_GBIAS_P_NSE controls how aggressively the EKF estimates the gyroscope's drift.

Gyro drift is the slow rotation reported by the sensor even when the drone is still.

The Engineer's View

Sets the process noise for the 3-axis gyro bias states.
$$ \dot{b}\_g = \mathcal{N}(0, \text{EK3\_GBIAS\_P\_NSE}) $$

Tuning & Behavior

  • Default Value: 1E-04 (0.0001)
  • Recommendation: Leave at default. If using very cheap gyros that drift wildly with temperature, increase this.

EK3_GLITCH_RAD

m
Default 25
Range 10 100

GPS glitch radius gate size (EK3_GLITCH_RAD)

Description

Defines the maximum allowed discrepancy between the predicted and measured GPS position.

EK3_GND_EFF_DZ

m
Default 4.0
Range 0.0 10.0

Baro height ground effect dead zone (EK3_GND_EFF_DZ)

Description

Compensates for the localized high-pressure zone created under a vehicle with lift rotors during takeoff and landing. This "ground effect" can cause barometric altitude to report negative values or spikes; the dead zone ignores these fluctuations.

EK3_GPS_CHECK

Default 31

GPS preflight check (EK3_GPS_CHECK)

Description

Bitmask selecting which specific GPS quality metrics (sat count, HDOP, velocity consistency) are checked before allowing the EKF to use GPS data or allowing the vehicle to arm.

Tuning & Behavior

  • Default Value: 31 (Standard rigorous checks)
  • Bitmask Examples:
    • Bit 0: sat count
    • Bit 1: HDOP
    • Bit 2: speed error

EK3_GPS_VACC_MAX

m
Default 0.0
Range 0.0 10.0

GPS vertical accuracy threshold (EK3_GPS_VACC_MAX)

Description

Safety threshold for using GPS for altitude. If the GPS reported vertical accuracy is worse than this value, the EKF will automatically fall back to the barometer.

  • 0 deactivates the threshold check.

EK3_GSF_RST_MAX

Default 2
Range 1 10

EKF3 GSF Reset Count Max (EK3_GSF_RST_MAX)

Description

EK3_GSF_RST_MAX is a safety limit for the Emergency Yaw Recovery system.

The Gaussian Sum Filter (GSF) is a backup system that tries to figure out the drone's heading using GPS movement if the compass fails. If the main EKF detects a "Compass Variance" (Heading Error), it can perform an emergency reset to align with the GSF's estimate. This parameter limits how many times it can do this per flight.

  • Why Limit It? If the GSF keeps triggering resets, something is fundamentally wrong (e.g. GPS glitching). Infinite resets could cause the drone to spin uncontrollably. Limiting it forces the drone to eventually fail-safe (Land) rather than constantly jumping its heading.

The Engineer's View

Defined in AP_NavEKF3 as _gsfResetMaxCount.
This counter is incremented every time resetYawToGSF() is successfully called. Once the limit is reached, the EKF will refuse further corrections from the GSF, likely leading to a "EKF Compass Variance" failsafe if the primary compass is still bad.

Tuning & Behavior

  • Default Value: 2.
  • Recommendation: Leave at 2. If your drone needs to reset its heading more than twice in one flight, you should not be flying.
  • Debug: Set to 10 only if you are testing the GSF algorithm itself and want to force multiple resets.

EK3_GSF_RUN_MASK

Default 3

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

Description

Enables the Gaussian Sum Filter (GSF) yaw estimator for specific EKF3 cores. GSF provides a yaw estimate derived from IMU and GPS velocity data, serving as a backup if the magnetometer is compromised.

EK3_GSF_USE_MASK

Default 3
Range 0 7

EKF3 GSF Use Mask (EK3_GSF_USE_MASK)

Description

EK3_GSF_USE_MASK selects the inputs for the emergency yaw estimator.

  • Bit 0 (1): Use GPS. (Standard).
  • Bit 1 (2): Use Airspeed. (For Planes).

Tuning & Behavior

  • Default Value: 3 (GPS + Airspeed).
  • Recommendation: Leave at default.

EK3_GYRO_P_NSE

rad/s
Default 0.015
Range 0.0001 0.1

Rate gyro noise (EK3_GYRO_P_NSE)

Description

Specifies the expected noise level in the gyroscopes for EKF3.

EK3_HGT_DELAY

ms
Default 60
Range 0 250

EKF3 Height Measurement Delay (EK3_HGT_DELAY)

Description

EK3_HGT_DELAY accounts for the "speed of sound" (and calculation) in your drone's height sensors.

Accelerometers are instantaneous, but Barometers and Rangefinders take time to process their data. By the time the Barometer tells the EKF "I am at 10 meters," that measurement is actually 60 milliseconds old—the drone has already moved. If the EKF fuses that "old" data with "new" IMU data, the math becomes inconsistent, leading to vertical oscillations.

EK3_HGT_DELAY allows the EKF to reach back into its "memory buffer" and compare the Baro data against exactly what the drone was doing 60ms ago. This alignment is critical for a rock-solid, jitter-free altitude hold.

  • Default (60ms): Optimized for standard MS5611 barometers.
  • Too Low: The drone may oscillate vertically at high frequency (vibrate).
  • Too High: The drone will be slow to respond to altitude changes and may "bounce" when stopping a climb.

The Mathematics

The EKF maintains a history of its internal states. When a height measurement ($z\_{alt}$) arrives at time $t$, the EKF doesn't compare it to the current state $\hat{x}(t)$. Instead, it looks up the state from $t - \text{DELAY}$:

$$ y\_{alt} = z\_{alt}(t) - H \cdot \hat{x}(t - \text{EK3\_HGT\_DELAY}) $$

Where $y\_{alt}$ is the Innovation (error) used to correct the filter. This ensures that the sensor data is always fused with the IMU state that produced it.

The Engineer's View

This parameter is the _hgtDelay_ms member in NavEKF3.

It is particularly important when using External Rangefinders over I2C or Serial. These sensors have their own internal filtering and communication latency. If your Lidar has a 100ms latency, but EK3_HGT_DELAY is only 60ms, the EKF will experience vertical "ringing" because its corrections are based on incorrect time-alignments.

Tuning & Behavior

  • Default Value: 60 ms
  • Range: 0 - 250 ms
  • Effect of Increasing: The drone trusts older data. Better for sensors with heavy internal filtering (slow Lidars).
  • Effect of Decreasing: The drone expects faster data. Better for high-speed SPI barometers.

Use Case Recommendations

  • Standard Pixhawk / Cube: Keep at 60. The internal Baro drivers are well-matched to this value.
  • Cheap Chinese Lidars (VL53L1X, etc.): Increase to 100. These sensors have significant communication lag over I2C.
  • High-Speed SPI Baro (BMP388/SPL06): Decrease to 20. Faster communication allows for a tighter altitude control loop.

Troubleshooting

  • Scenario: Drone bobs up and down rhythmically (about 2-3 times per second) specifically when using a new Rangefinder.
    • Diagnosis: Height sensor delay mismatch. The EKF is comparing current height to past movements incorrectly.
    • Fix: Increase EK3_HGT_DELAY by 20ms increments until the bobbing stops.

EK3_HGT_I_GATE

%
Default 500
Range 100 1000

EKF3 Height Innovation Gate (EK3_HGT_I_GATE)

Description

EK3_HGT_I_GATE is the "Bouncer" for your altitude data.

The EKF predicts where the drone should be based on its motors and accelerometers. When the barometer (or GPS) provides a new height reading, the EKF calculates the difference (the "Innovation"). If the reading is too different from the prediction (e.g., a massive sudden jump), the "Gate" rejects it to prevent the drone from rocketing up or down due to a sensor glitch.

The Mathematics

The innovation $y$ and its covariance $S$ are used to calculate the normalized innovation squared (NIS):

$$ ext{NIS} = y^T S^{-1} y $$

The measurement is rejected if:

$$ ext{NIS} > \left( \frac{\text{EK3\_HGT\_I\_GATE}}{100} \right)^2 $$

A value of 500 means 5 standard deviations.

Tuning & Behavior

  • Default Value: 500 (5 Sigma).
  • Glitchy Baro: If you see "EKF primary changed: 0" frequently when flying near ground effect or in wind, you might need to Increase this value to 700 or 800.
  • Safety: Setting this too high makes the EKF more vulnerable to slow sensor drift.

EK3_HRT_FILT

Hz
Default 2.0
Range 0.1 30.0

EKF3 Height Rate Filter Frequency (EK3_HRT_FILT)

Description

EK3_HRT_FILT tunes the vertical velocity estimator.

It combines the accelerometer data (fast, noisy) with the barometer/GPS data (slow, smooth). This frequency determines the "crossover point."

Tuning & Behavior

  • Default Value: 2.0 Hz.
  • Higher Value: More responsive to rapid climbs, but noisier.
  • Lower Value: Smoother velocity estimate, but slight lag.

EK3_IMU_MASK

Default 3

Bitmask of active IMUs (EK3_IMU_MASK)

Description

Defines which physical IMUs will have an associated EKF3 core instance. Running multiple cores provides redundancy; the flight controller will automatically switch to the healthiest core.

Tuning & Behavior

  • Default Value: 3 (IMU1 and IMU2)
  • Bitmask Examples: 1:IMU1 only, 3:IMU1 & IMU2, 7:IMU1, IMU2 & IMU3.
  • Requires reboot to take effect.

EK3_LOG_LEVEL

Default 0
Range 0 3

Logging Level (EK3_LOG_LEVEL)

Description

Controls the verbosity of EKF3 data written to the log.

  • 0: Full logging (standard)
  • 3: Disables EKF3 streaming logs entirely (to save CPU/bandwidth)

EK3_MAGB_P_NSE

Gauss/s
Default 0.001
Range 0.00001 0.01

Body magnetic field process noise (EK3_MAGB_P_NSE)

Description

Specifies how quickly EKF3 adapts its estimate of internal magnetic bias.

EK3_MAGE_P_NSE

Gauss/s
Default 0.001
Range 0.00001 0.01

Earth magnetic field process noise (EK3_MAGE_P_NSE)

Description

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

EK3_MAG_CAL

Default 3
Range 0 4

Magnetometer default fusion mode (EK3_MAG_CAL)

Description

Configures the EKF3 magnetometer processing logic. Identical in behavior to EK2_MAG_CAL.

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

EK3_MAG_EF_LIM

mGauss
Default 50
Range 0 500

EKF3 Magnetic Earth Field Limit (EK3_MAG_EF_LIM)

Description

EK3_MAG_EF_LIM acts as a sanity check for the compass.

The autopilot knows roughly what the earth's magnetic field should look like at your location (based on the WMM table). If the EKF tries to learn a magnetic offset larger than this limit, it assumes the compass is being jammed by a localized magnetic anomaly (like a power line) and rejects the update.

Tuning & Behavior

  • Default Value: 50 mGauss.
  • Recommendation: Increase to 100 if you fly in areas with strong magnetic variations (e.g. volcanic soil).

EK3_MAG_I_GATE

Default 300
Range 100 1000

Compass Innovation Gate (EK3_MAG_I_GATE)

Description

EK3_MAG_I_GATE is the "BS Filter" for the compass.

The EKF is constantly predicting what the magnetic field should be based on its current heading. When it gets a new measurement from the physical compass, it calculates the difference (the "Innovation"). If that difference is too large, the EKF assumes the compass has gone haywire (maybe it's near a magnet) and rejects the data to prevent a crash.

  • Low Value (e.g., 100): Very strict. If the compass signal is even slightly noisy, the EKF will ignore it. This is safe but can lead to "Compass Unhealthy" warnings.
  • High Value (e.g., 500): Very relaxed. The EKF will trust almost anything the compass says. Dangerous if the compass is actually being distorted by interference.

The Mathematics

The gate uses a Statistical Distance (Mahalanobis Distance) check.
The innovation $y = z - H\hat{x}$ is checked against the innovation covariance $S$:
$$ y^T S^{-1} y \leq \text{GATE}^2 $$

If the error squared exceeds the gate threshold, the measurement is discarded.

The Engineer's View

Used in the measurement update loop of AP_NavEKF3.
A value of 300 corresponds to a 3-sigma gate (99.7% confidence interval). Measurements outside this are statistically likely to be errors rather than valid movement.

Tuning & Behavior

  • Default Value: 300
  • Recommendation: Keep at 300.
  • Troubleshooting: If you get constant "EKF Compass Innovation" errors but you are sure your compass is well-calibrated and away from metal, you can increase this to 500 to stop the warnings. However, this is usually masking a physical hardware issue (vibration or interference).

EK3_MAG_MASK

Default 0
Range 0 255

EKF3 Magnetometer Mask (EK3_MAG_MASK)

Description

EK3_MAG_MASK selects which compasses the EKF is allowed to listen to.

By default (0), the EKF uses the first healthy compass it finds. This mask forces it to use specific sensors.

  • Bit 0: Compass 1.
  • Bit 1: Compass 2.
  • Bit 2: Compass 3.

Tuning & Behavior

  • Default Value: 0 (All).
  • Recommendation: If you have an external GPS/Compass and an internal noisy compass, set this to 1 (Bit 0) to force the EKF to only use the external one.

EK3_MAG_M_NSE

Gauss
Default 0.05
Range 0.01 0.5

Magnetometer measurement noise (EK3_MAG_M_NSE)

Description

Specifies the expected noise level in the magnetometer data.

EK3_MAX_FLOW

rad/s
Default 2.5f
Range 1.0 4.0

Maximum valid optical flow rate (EK3_MAX_FLOW)

Description

This parameter sets a hard limit on the optical flow rate (angular velocity of the visual texture) that the Extended Kalman Filter (EKF) will accept. If the flow sensor reports a value higher than this, it is assumed to be a glitch (e.g., lighting change, shadow, or sensor error) or a maneuver exceeding the sensor's capability, and the measurement is rejected to prevent position divergence.

The Mathematics

$$ \text{Reject} \iff |\vec{\omega}\_{\text{flow}}| > \text{EK3\_MAX\_FLOW} $$

The Engineer's View

Defined in libraries/AP_NavEKF3/AP_NavEKF3.cpp. Used in the optical flow fusion logic. High flow rates often correlate with poor signal quality or motion blur, making the data unreliable.

Tuning & Behavior

  • Default Value: 2.5 $rad/s$ (~143 $deg/s$)
  • Range: 1.0 - 4.0 $rad/s$
  • Tuning: Increase slightly for highly agile quadcopters flying close to the ground, but be aware that sensor noise often increases at high rates.

EK3_NOAID_M_NSE

m/s
Default 10.0
Range 1.0 50.0

EKF3 No-Aid Measurement Noise (EK3_NOAID_M_NSE)

Description

EK3_NOAID_M_NSE prevents the EKF from exploding when GPS is lost.

When all position sensors fail, the EKF assumes the drone is stationary (or moving at constant velocity) with a very high uncertainty. This parameter sets that uncertainty.

Tuning & Behavior

  • Default Value: 10.0 m/s.

EK3_OGNM_TEST_SF

Default 1.0
Range 1.0 10.0

EKF3 On-Ground Movement Test Scale (EK3_OGNM_TEST_SF)

Description

EK3_OGNM_TEST_SF helps the EKF decide if it is flying.

The EKF assumes the drone is stationary on the ground. If the gyro/accel indicates movement that exceeds a threshold, the EKF switches to "In Air" mode. This parameter scales that threshold.

Tuning & Behavior

  • Default Value: 1.0.
  • Recommendation: Increase if you are launching from a moving boat or vehicle.

EK3_OGN_HGT_MASK

Default 0
Range 0 7

EKF3 Origin Height Mask (EK3_OGN_HGT_MASK)

Description

EK3_OGN_HGT_MASK keeps your "Mean Sea Level" (MSL) altitude accurate even when you are flying using a Barometer or Lidar.

If you fly using EK3_SRC1_POSZ = 1 (Baro), the EKF tracks your height relative to the takeoff point. However, barometers drift with weather changes. This parameter tells the EKF to use the GPS height (if available) to slowly correct the "Origin" height in the background, so that your logged global altitude remains valid over long flights.

Tuning & Behavior

  • Bit 0: Correct datum when using Baro height.
  • Bit 1: Correct datum when using Range Finder height.
  • Bit 2: Apply corrections to Local Position (instead of Origin). Experimental.

Recommendation

  • Default Value: 0.
  • Surveying: If accurate MSL geotags are critical, set Bit 0 (Value 1).

EK3_OPTIONS

Default 0
Range 0 1024

EKF3 Options (EK3_OPTIONS)

Description

EK3_OPTIONS is a "Power User" menu for the estimator.

  • Bit 0: Enable "Tilt Alignment" during movement.
  • Bit 1: Disable GPS glitch protection.
  • Bit 2: Enable high-accuracy gyro bias learning.

Tuning & Behavior

  • Default Value: 0.
  • Recommendation: Leave at 0 unless you have a specific reason to change it (e.g., debugging a compass issue).

EK3_POSNE_M_NSE

m
Default 0.5
Range 0.1 10.0

GPS horizontal position noise (EK3_POSNE_M_NSE)

Description

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

EK3_POS_I_GATE

Default 500
Range 100 1000

EKF3 Position Innovation Gate (EK3_POS_I_GATE)

Description

EK3_POS_I_GATE is the "glitch detector" for your drone's position. It determines how far the GPS data can disagree with the drone's internal estimate before the EKF3 decides the GPS is lying.

In a Kalman Filter, the difference between the expected measurement and the actual measurement is called the Innovation. If your drone thinks it's at Point A, but the GPS suddenly says it's at Point B (100 meters away), the Innovation is huge. The "Gate" is a mathematical boundary—if the error is inside the gate, it's considered "normal noise" and the EKF updates its position. If it's outside the gate, it's considered a "glitch" and is ignored.

  • Low Value (e.g. 100): Very strict. The EKF will reject even small GPS jumps. This is safe but can lead to the EKF "timing out" and losing its position estimate if the GPS is consistently slightly off.
  • High Value (e.g. 1000): Very relaxed. The EKF will accept large position jumps. This allows for faster recovery from errors but increases the risk of the drone "darting" toward a fake GPS coordinate.

The Mathematics

The EKF uses a statistical test (Chi-Squared) to determine if a measurement is valid. The gate ($G$) is applied to the Normalized Innovation Squared ($NIS$):

$$ NIS = \vec{y}^T \mathbf{S}^{-1} \vec{y} \leq G^2 $$

Where:

  • $\vec{y}$ is the Innovation vector (Measurement - Prediction).
  • $\mathbf{S}$ is the Innovation Covariance (Total expected uncertainty).
  • $G$ is the value derived from EK3_POS_I_GATE.

Scale: The value in the GCS (e.g., 500) represents a standard deviation multiplier. A value of 500 corresponds to a "5-sigma" gate, which is extremely statistically unlikely to occur by chance (~0.00006% probability).

The Engineer's View

This parameter is the _gpsPosInnovGate member in NavEKF3.

It is checked during the AP_NavEKF3_PosVelFusion.cpp loop. If a measurement fails the gate, it is logged as an EKF Primary Check Failure. If measurements fail consistently for more than a second, the EKF will trigger a "Reset" or an "EKF Lane Switch," assuming that its internal state (not the sensor) is the one that is wrong.

Tuning & Behavior

  • Default Value: 500 (Standard)
  • Range: 100 - 1000
  • Effect of Increasing: Faster recovery from large position resets. Better for high-speed flight where position uncertainty is naturally high.
  • Effect of Decreasing: Better protection against small GPS multipath jumps. Essential for high-precision autonomous missions near obstacles.

Use Case Recommendations

  • Open Field Flight: Keep Default (500).
  • RTK Precision Survey: Decrease to 200. Since RTK is extremely accurate, any innovation larger than 20cm is almost certainly a sensor error and should be rejected instantly.
  • Rapid Racing / High G-Force: Increase to 800. High-speed maneuvers create high uncertainty; a wider gate prevents the EKF from "locking out" the GPS during sharp turns.

Troubleshooting

  • Scenario: Drone refuses to enter Loiter, and the GCS shows "EKF Position Variance."
    • Diagnosis: The GPS data is consistently failing the innovation gate.
    • Fix: If the GPS signal is clear, increase EK3_POS_I_GATE to 750 to help the EKF re-sync.
  • Scenario: Drone "darts" 5 meters to the side before coming back.
    • Diagnosis: EK3_POS_I_GATE is too high, allowing the EKF to follow a bad GPS sample.
    • Fix: Reduce to 300.

EK3_PRIMARY

Default 0
Range 0 2

Primary core number (EK3_PRIMARY)

Description

Selects the initial primary EKF core. Lane 0 corresponds to the first IMU enabled in EK3_IMU_MASK.

EK3_RNG_I_GATE

%
Default 500
Range 100 1000

EKF3 Rangefinder Innovation Gate (EK3_RNG_I_GATE)

Description

EK3_RNG_I_GATE filters out Lidar "Glitches."

Lidars often give false readings when flying over grass, water, or bright sunlight. This gate ensures that a sudden jump from 2m to 50m is ignored if the IMU says the drone hasn't moved.

Tuning & Behavior

  • Default Value: 500 (5 Sigma).

EK3_RNG_M_NSE

m
Default 0.5
Range 0.1 5.0

EKF3 Rangefinder Measurement Noise (EK3_RNG_M_NSE)

Description

EK3_RNG_M_NSE sets the trust level for the Lidar.

  • 0.1: Highly trusted. Use for precision landing on flat surfaces.
  • 0.5 (Default): Standard trust. Good for general flight.
  • 1.0+: Low trust. Use for sonars or noisy environments.

Tuning & Behavior

  • Default Value: 0.5 m.

EK3_RNG_USE_HGT

%
Default -1
Range -1 70

EKF3 Rangefinder Use Height (EK3_RNG_USE_HGT)

Description

EK3_RNG_USE_HGT allows the EKF to automatically switch to Lidar altitude when close to the ground.

If set to 70%, and your Lidar has a 10m range, the EKF will switch from Baro to Lidar when you descend below 7 meters. This provides terrain following for landing without needing to change EK3_SRC1_POSZ.

Tuning & Behavior

  • -1 (Default): Disabled. Lidar is only used if EK3_SRCx_POSZ = 2 (Rangefinder).
  • 0-70: Enabled. Percentage of RNGFND_MAX_CM.

EK3_RNG_USE_SPD

m/s
Default 2.0
Range 2.0 6.0

EKF3 Rangefinder Use Speed (EK3_RNG_USE_SPD)

Description

EK3_RNG_USE_SPD prevents using Lidar altitude when flying fast.

Many Lidars struggle when the ground is rushing by (motion blur) or when the drone is pitched over (measuring diagonal distance instead of vertical). This parameter forces a switch back to Baro/GPS if the drone exceeds this speed.

Tuning & Behavior

  • Default Value: 2.0 m/s.
  • Recommendation: Keep low (2-6 m/s) to ensure Lidar is only used for takeoff/landing hover.

EK3_SRC1_POSXY

Default 3

Position Horizontal Source (Primary) (EK3_SRC1_POSXY)

Description

Defines where the EKF3 algorithm gets its primary horizontal (latitude/longitude) position data.

Tuning & Behavior

  • Default Value: 3 (GPS)
  • Values: 0:None, 3:GPS, 4:Beacon, 6:ExternalNav
  • Most common setting is GPS.

EK3_SRC1_POSZ

Default 1

Position Vertical Source (Primary) (EK3_SRC1_POSZ)

Description

Defines where the EKF3 algorithm gets its primary altitude data.

Tuning & Behavior

  • Default Value: 1 (Baro)
  • Values: 0:None, 1:Baro, 2:RangeFinder, 3:GPS, 4:Beacon, 6:ExternalNav
  • Baro is standard for most flights.

EK3_SRC1_VELXY

Default 3

Velocity Horizontal Source (Primary) (EK3_SRC1_VELXY)

Description

Defines where the EKF3 algorithm gets its primary horizontal speed and direction data.

Tuning & Behavior

  • Default Value: 3 (GPS)
  • Values: 0:None, 3:GPS, 4:Beacon, 5:OpticalFlow, 6:ExternalNav, 7:WheelEncoder

EK3_SRC1_VELZ

Default 3
Range 0 6

Vertical Velocity Source (EK3_SRC1_VELZ)

Description

EK3_SRC1_VELZ defines where the Extended Kalman Filter (EKF) gets its vertical velocity (climb/descent rate) information.

Correct vertical velocity is essential for altitude hold and vertical position control. Most GPS modules provide a high-quality vertical velocity measurement based on Doppler shift, which is more responsive than deriving velocity from pressure changes (Barometer).

  • 0: None.
  • 3: GPS. (Standard for most outdoor drones).
  • 4: Beacon.
  • 6: ExternalNav. (For VIO or OptiTrack systems).

Tuning & Behavior

  • Default: 3 (GPS).
  • Indoor Flight: If flying indoors without GPS, this is typically set to 0 or provided by ExternalNav.

EK3_SRC1_YAW

Default 1

Yaw Source (Primary) (EK3_SRC1_YAW)

Description

Defines where the EKF3 algorithm gets its primary heading (yaw) data.

Tuning & Behavior

  • Default Value: 1 (Compass)
  • Values: 0:None, 1:Compass, 2:GPS, 3:GPS with Compass Fallback, 6:ExternalNav, 8:GSF
  • Option 2 (GPS) refers to "moving baseline" dual-antenna GPS yaw.

EK3_SRC2_POSXY

Default (int8_t
Range null

Position Horizontal Source (Secondary)

Note: This parameter functions identically to EK3_SRC1_POSXY.

EK3_SRC2_POSZ

Default (int8_t
Range null

Position Vertical Source (Secondary)

Note: This parameter functions identically to EK3_SRC1_POSZ.

EK3_SRC2_VELXY

Default (int8_t
Range null

Velocity Horizontal Source (Secondary)

Note: This parameter functions identically to EK3_SRC1_VELXY.

EK3_SRC2_VELZ

Default (int8_t
Range null

Velocity Vertical Source (Secondary)

Note: This parameter functions identically to EK3_SRC1_VELZ.

EK3_SRC2_YAW

deg
Default 0
Range null

Custom yaw

Note: This parameter functions identically to EK3_SRC1_YAW.

EK3_SRC3_POSXY

Default (int8_t
Range null

Position Horizontal Source (Tertiary)

Note: This parameter functions identically to EK3_SRC1_POSXY.

EK3_SRC3_POSZ

Default (int8_t
Range null

Position Vertical Source (Tertiary)

Note: This parameter functions identically to EK3_SRC1_POSZ.

EK3_SRC3_VELXY

Default (int8_t
Range null

Velocity Horizontal Source (Tertiary)

Note: This parameter functions identically to EK3_SRC1_VELXY.

EK3_SRC3_VELZ

Default (int8_t
Range null

Velocity Vertical Source (Tertiary)

Note: This parameter functions identically to EK3_SRC1_VELZ.

EK3_SRC3_YAW

deg
Default 0
Range null

Custom yaw

Note: This parameter functions identically to EK3_SRC1_YAW.

EK3_SRC_OPTIONS

Default 1

EKF Source Options (EK3_SRC_OPTIONS)

Description

Advanced configuration bitmask for blending or switching between multiple sensor sources (e.g., GPS and Optical Flow).

Tuning & Behavior

  • Default Value: 1 (FuseAllVelocities)
  • Bitmask:
    • Bit 0: FuseAllVelocities (Allows simultaneous use of multiple velocity sources)
    • Bit 1: AlignExtNavPos (Aligns external nav position when using optical flow)

EK3_TAU_OUTPUT

cs
Default 25
Range 10 50

EKF3 Output Time Constant (EK3_TAU_OUTPUT)

Description

EK3_TAU_OUTPUT is the final smoothing filter for the EKF.

The raw EKF state can jump discretely when a GPS update arrives (5Hz or 10Hz). The "Output Observer" smooths these jumps to provide a continuous 400Hz stream to the position controller.

Tuning & Behavior

  • Default Value: 25 (0.25 seconds).
  • Lower Value: Faster response, more jitter.
  • Higher Value: Smoother, more lag.

EK3_TERR_GRAD

m/m
Default 0.1
Range 0 0.5

EKF3 Terrain Gradient (EK3_TERR_GRAD)

Description

EK3_TERR_GRAD tells the EKF how hilly the ground is expected to be.

This is used for Optical Flow and Terrain Following. If the Lidar distance changes rapidly, the EKF uses this parameter to decide if the drone moved up/down or if the ground moved (a hill).

Tuning & Behavior

  • Default Value: 0.1 (10% slope).
  • Hilly Terrain: Increase to 0.5 if flying over steep hills.

EK3_VELD_M_NSE

m/s
Default 0.5
Range 0.05 5.0

GPS vertical velocity noise (EK3_VELD_M_NSE)

Description

Specifies the expected noise level in the GPS vertical velocity data for EKF3.

EK3_VELNE_M_NSE

m/s
Default 0.5
Range 0.05 5.0

GPS horizontal velocity noise (EK3_VELNE_M_NSE)

Description

Specifies the expected noise level in the GPS horizontal velocity data for EKF3.

EK3_VEL_I_GATE

Default 300
Range 100 1000

EKF3 Velocity Innovation Gate (EK3_VEL_I_GATE)

Description

EK3_VEL_I_GATE is the "speed trap" for your drone's sensors. It determines how much a sensor's reported speed can disagree with the drone's internal math before the data is rejected as a glitch.

If your drone thinks it's stationary, but the GPS suddenly reports a speed of 50 m/s (common in poor signal conditions), the Innovation (error) is massive. EK3_VEL_I_GATE sets the threshold for this error. If the reported speed is outside this gate, the EKF ignores it, assuming the GPS is having a momentary glitch.

  • Low Value (e.g. 100): Very strict. Prevents the drone from jerking or twitching if the GPS speed jumps, but can cause the EKF to lose sync if the drone is actually maneuvering aggressively.
  • High Value (e.g. 800): Very relaxed. The EKF will follow even large jumps in speed data.
  • Default (300): A balanced 3-sigma gate that is robust for standard flight.

The Mathematics

The gate ($G$) is part of the Chi-Squared consistency check:

$$ \vec{y}\_v^T \mathbf{S}\_v^{-1} \vec{y}\_v \leq G^2 $$

Where:

  • $\vec{y}v$ is the Velocity Innovation ($V{sensor} - V\_{predicted}$).
  • $\mathbf{S}\_v$ is the Innovation Covariance matrix for velocity.
  • $G$ is derived from EK3_VEL_I_GATE.

Scaling: The value (300) represents a percentage of the standard deviation. 300 means a "3-sigma" threshold, which covers 99.7% of all expected sensor variations. Anything beyond this is statistically "impossible" and likely a glitch.

The Engineer's View

This parameter is the _gpsVelInnovGate member in NavEKF3.

It is applied in AP_NavEKF3_PosVelFusion.cpp. Velocity gating is more critical than position gating for Flight Damping. If a bad velocity sample passes the gate, it instantly creates a massive acceleration demand in the PID loops, causing a violent "jerk." Keeping this gate tight (e.g. 300) is what makes ArduPilot feel smooth even in noisy GPS environments.

Tuning & Behavior

  • Default Value: 300
  • Range: 100 - 1000
  • Effect of Increasing: The drone is less likely to lose "EKF Health" during extreme 3D maneuvers or high-speed racing.
  • Effect of Decreasing: Smoother flight; more aggressive rejection of GPS speed spikes.

Use Case Recommendations

  • Standard Multirotor: Keep Default (300).
  • High-Speed Racing Drone: Increase to 500 - 600. High-G turns create large velocity innovations that can exceed 3-sigma; a wider gate prevents the EKF from "locking out" the sensors during the turn.
  • Precision Docking / Automation: Decrease to 150. In slow, precision movements, you want to reject any speed noise immediately to prevent the drone from "twitching" near the docking target.

Troubleshooting

  • Scenario: GCS reports "EKF Velocity Variance" every time I perform a sharp turn.
    • Diagnosis: The maneuvers are so aggressive that the EKF's prediction is lagging behind the sensor, causing the error to hit the gate limit.
    • Fix: Increase EK3_VEL_I_GATE to 500.
  • Scenario: Drone "lunges" forward randomly for a fraction of a second.
    • Diagnosis: EK3_VEL_I_GATE is too high, letting a bad GPS velocity sample corrupt the filter.
    • Fix: Reduce to 200.

EK3_VIS_VERR_MAX

m/s
Default 0.9
Range 0.5 5.0

EKF3 Visual Odometry Max Error (EK3_VIS_VERR_MAX)

Description

EK3_VIS_VERR_MAX defines the trust floor for Visual Odometry.

When the VO system reports poor quality (e.g., dark room, featureless wall), the EKF uses this error value.

Tuning & Behavior

  • Default Value: 0.9 m/s.

EK3_VIS_VERR_MIN

m/s
Default 0.1
Range 0.05 0.5

EKF3 Visual Odometry Min Error (EK3_VIS_VERR_MIN)

Description

EK3_VIS_VERR_MIN sets the trust ceiling for Visual Odometry (VO).

VO systems (like Intel RealSense or Zed) report a "Quality" metric. When quality is 100%, the EKF uses this error value.

  • 0.1: Very confident.
  • 0.5: Less confident.

Tuning & Behavior

  • Default Value: 0.1 m/s.

EK3_WENC_VERR

m/s
Default 0.1
Range 0.05 1.0

EKF3 Wheel Encoder Velocity Error (EK3_WENC_VERR)

Description

EK3_WENC_VERR tells the EKF how accurate the wheel encoders are.

If you are using wheel odometry for non-GPS navigation (e.g., a rover indoors), this parameter sets the trust level.

  • Low Value: High trust. The EKF will rely heavily on the wheels to estimate speed.
  • High Value: Low trust. The EKF will rely more on the IMU.

Tuning & Behavior

  • Default Value: 0.1 m/s.
  • Slippery Surface: Increase to 0.5 if the wheels slip often.

EK3_WIND_PSCALE

Default 0.5
Range 0.0 1.0

EKF3 Wind Process Noise Scale (EK3_WIND_PSCALE)

Description

EK3_WIND_PSCALE determines how much the EKF allows the wind estimate to change while the drone is turning.

When the drone maneuvers aggressively, it is harder to separate inertial forces from wind forces. This parameter tells the EKF to increase the uncertainty (noise) of the wind state during these times, allowing the estimate to shift faster to match reality.

  • High Value (1.0): Wind estimate adapts rapidly during turns.
  • Low Value (0.0): Wind estimate is "frozen" during turns.

The Engineer's View

This parameter scales the _windProcessNoise dynamically based on the maneuver status.
$$ Q\_{wind} = Q\_{base} \times (1.0 + \text{Maneuver} \times \text{EK3\_WIND\_PSCALE}) $$

Tuning & Behavior

  • Default Value: 0.5.
  • Gliders/Soaring: Increase to 1.0. You want the wind estimate to update instantly as you circle in a thermal.
  • Mapping Plane: Decrease to 0.1. You want a stable, averaged wind estimate for uniform track spacing.

EK3_WIND_P_NSE

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

Wind velocity process noise (EK3_WIND_P_NSE)

Description

Controls how quickly EKF3 adapts to changing wind conditions.

EK3_YAW_I_GATE

%
Default 300
Range 100 1000

EKF3 Yaw Innovation Gate (EK3_YAW_I_GATE)

Description

EK3_YAW_I_GATE prevents the drone from following a "bad" compass.

If you fly near a large metal structure (like a bridge or power pylon), the magnetic field will twist. The compass will report a heading that is wildly different from what the Gyroscope expects. This gate detects that "Innovation" (disagreement) and rejects the compass data, forcing the drone to rely on Gyro Dead-Reckoning until it flies past the interference.

  • Low Value (100): Very strict. Reject compass at the slightest hint of trouble. Good for flying near steel.
  • High Value (500): Relaxed. Trust the compass even if it jumps.

The Mathematics

The Normalized Innovation Squared (NIS) for yaw is compared against the gate:
$$ \text{Yaw Error}^2 / \text{Variance} < (\text{GATE}/100)^2 $$

The Engineer's View

This is the primary defense against "Toilet Bowling" caused by magnetic interference. If the gate rejects the compass for too long (> 10 seconds), the EKF will declare a "Compass Variance" failsafe and may switch to GSF (GPS Yaw) if available.

Tuning & Behavior

  • Default Value: 300 (3-Sigma).
  • Recommendation: Keep at 300.
  • High Interference: If you must fly indoors near metal beams, reducing this to 100 can help the drone ignore the magnetic distortions and fly purely on Gyro (drift) for short periods.

EK3_YAW_M_NSE

rad
Default 0.5
Range 0.05 1.0

Yaw measurement noise (EK3_YAW_M_NSE)

Description

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