ekfInterface#

Executive Summary#

This class provides an interface for Extended (and Classical) Kalman Filters. Modules which inherit from it will benefit from having the core functionality of these basic filters. This class inherits from the Kalman Filter interface.

The math is derived primarily using the equations in Tapley, Schutz, and Born’s Statistical Orbit Determination textbook Chapter 4. This contains further information on this module’s mathematical framework, and the flow diagrams describing the algorithm implementations.

Virtual and Private method descriptors#

The following table lists all the module input and output messages. The module msg connection is set by the user from python. The msg type contains a link to the message structure definition, while the description provides information on what this message is used for.

Interface methods which remain private#

Method Name

Method Function

Protected or Private

Virtual or not

timeUpdate

filter time update

private

non-virtual

measurementUpdate

filter measurement update in the presence of measurements

private

non-virtual

computeResiduals

compute filter post fit residuals

private

non-virtual

computeKalmanGain

compute the Kalman

private

non-virtual

updateCovariance

measurement update for the covariance

private

non-virtual

ckfUpdate

update using the classical kalman filter

private

non-virtual

ekfUpdate

update using the extended kalman filter

private

non-virtual

Module assumptions and limitations#

The module inherits all assumptions made while implementing a Kalman filter:
  • Observability considerations

  • Gaussian covariances

  • Linearity limits

  • and more

Otherwise, the limitations are governed by the measurement model and dynamics models relative to the required performance.

User Guide#

When instantiating this filter, the user must use the FilterType enum class to chose whether this is a Linear (Classical) Kalman Filter or an Extended Kalman Filter. The Extended Kalman Filter updates the reference state at each measurement update.

This section also lists all the setters and getters that are defined by the interface.

Interface methods which remain private#

Method Name

Method Function

Necessity

set/getMinimumCovarianceNormForEkf

if using an EKF, set the covariance infinite norm that will switch from CKF updates to EKFs

optional

set/getConstantRateStates

if using constant rates (not estimated by the filter) that integrate the state linearly, set this rate component

necessary

class EkfInterface : public KalmanFilter#

Extended or Classical/Linear Kalman Filter base class.

Subclassed by LinearODeKF

Public Functions

void reset(uint64_t currentSimNanos) override#

Reset all of the filter states, including the custom reset

Parameters:

currentSimNanos – The clock time at which the function was called (nanoseconds)

Returns:

void

void setFilterDynamicsMatrix(const std::function<const Eigen::MatrixXd(const double, const FilterStateVector&)> &dynamicsMatrixCalculator)#

Get the filter dynamics matrix (A = df/dX evaluated at the reference)

Returns:

Eigen::VectorXd stateInitial

void setMinimumCovarianceNormForEkf(double infiniteNorm)#

Set a minimum value (infinite norm, meaning maximal term) of the covariance before switching to Extended KF updates. This prevents divergence if the initial covariance is high and the state changes too abruptly

Parameters:

double – infiniteNorm

Returns:

void

double getMinimumCovarianceNormForEkf() const#

Get the minimum value of the covariance before switching to Extended KF updates.

Returns:

double infiniteNorm