Extended Kalman Filter (EKF)

../_images/advanced-configuration-ekf.png

Copter and Plane can use an Extended Kalman Filter (EKF) algorithm to estimate vehicle position, velocity and angular orientation based on rate gyroscopes, accelerometer, compass, GPS, airspeed and barometric pressure measurements.

The advantage of the EKF over the simpler complementary filter algorithms (i.e. “Inertial Nav”), is that by fusing all available measurements it is better able to reject measurements with significant errors. This makes the vehicle less susceptible to faults that affect a single sensor. EKF also enables measurements from optional sensors such as optical flow and laser range finders to be used to assist navigation.

Current stable version of ArduPilot use the EKF2 as their primary attitude and position estimation source with DCM running quietly in the background. If the flight controller has two (or more) IMUs available, two EKF “cores” (i.e. two instances of the EKF) will run in parallel, each using a different IMU. At any one time, only the output from a single EKF core is ever used, that core being the one that reports the best health which is determined by the consistency of its sensor data.

Most user should not need to modify any EKF parameters but the information below provides some information on those parameters that are most commonly changed. More detailed information can be found on the developer EKF wiki page.

Choosing the EKF and number of cores

AHRS_EKF_USE: set to “1” to use the EKF, “0” to use DCM for attitude control and inertial nav (Copter-3.2.1) or ahrs dead reckoning (Plane) for position control. In Copter-3.3 (and higher) this parameter is forced to “1” and cannot be changed.

AHRS_EKF_TYPE: set to “2” to use EKF2 for attitude and position estimation, “3” for EKF3.

EK2_ENABLE, EK3_ENABLE: set to “1” to enable the EKF2 and/or EKF3 respectively.

EK2_IMU_MASK, EK3_IMU_MASK: a bitmask specifying which IMUs (i.e. accelerometer/gyro) to use. An EKF “core” (i.e. a single EKF instance) will be started for each IMU specified.

  • 1: starts a single EKF core using the first IMU
  • 2: starts a single EKF core using only the second IMU
  • 3: starts two separate EKF cores using the first and second IMUs respectively

Note

Plane and Rover will fall back from EKF2 or EKF3 to DCM if the EKF becomes unhealthy or the EKF is not fusing GPS data despite the GPS having 3D Lock. There is no fallback from EKF3 to EKF2 (or EKF2 to EKF1)

Warning

Using the parameters above it is possible to run up to 5 AHRSs in parallel at the same time (DCMx1, EKF2x2, EKF3x2) but this can result in performance problems so if running EKF2 and EKF3 in parallel, set the IMU_MASK to reduce the total number of cores.

Commonly modified parameters

EK2_ALT_SOURCE which sensor to use as the primary altitude source

  • 0 : use barometer (default)
  • 1 : use range finder. This can be used for environments where the barometer data is very noisy and the ground is relatively flat (i.e. indoors where an airconditioner may cause sudden pressure changes). This should not be used if the intention is to perform terrain following. For terrain terrain following see copter and plane specific terrain following instructions).
  • 2 : use GPS. Useful when GPS quality is very good and barometer drift could be a problem. For example if the vehicle will perform long distance missions with altitude changes of >100m.

EK2_ALT_NOISE: Default is “1.0”. Lower number reduces reliance on accelerometers, increases reliance on barometer.

EK2_GPS_TYPE: Controls how GPS is used.

  • 0 : use 3D velocity & 2D position from GPS
  • 1 : use 2D velocity & 2D position (GPS velocity does not contribute to altitude estimate)
  • 2: use 2D position
  • 3 : no GPS (will use optical flow only if available)

As mentioned above, a more detailed overview of EKF theory and tuning parameters is available on the developer wiki’s Extended Kalman Filter Navigation Overview and Tuning.