Resurgence (PY2022)
Codebase for the Husky Robotics 2021-2022 rover Resurgence
Loading...
Searching...
No Matches
filters::ExtendedKalmanFilter< stateDim, inputDim, outputDim, processNoiseDim, outputNoiseDim > Class Template Reference

Implements a discrete-time EKF. More...

#include <ExtendedKalmanFilter.h>

Inheritance diagram for filters::ExtendedKalmanFilter< stateDim, inputDim, outputDim, processNoiseDim, outputNoiseDim >:
Collaboration diagram for filters::ExtendedKalmanFilter< stateDim, inputDim, outputDim, processNoiseDim, outputNoiseDim >:

Public Types

using state_t = Eigen::Matrix<double, stateDim, 1>
 
using output_t = Eigen::Matrix<double, outputDim, 1>
 
using input_t = Eigen::Matrix<double, inputDim, 1>
 
using statefunc_t
 
using outputfunc_t
 
using processnoise_t = Eigen::Matrix<double, processNoiseDim, 1>
 
using outputnoise_t = Eigen::Matrix<double, outputNoiseDim, 1>
 

Public Member Functions

 ExtendedKalmanFilter (const statefunc_t &stateFunc, const outputfunc_t &outputFunc, const statespace::NoiseCovMat< stateDim, processNoiseDim, inputDim > &processNoise, const statespace::NoiseCovMat< stateDim, outputNoiseDim, outputDim > &outputNoise, double dt)
 Create a new discrete-time EKF.
 
void predict (const Eigen::Matrix< double, inputDim, 1 > &input) override
 Use the model to predict the next system state, given the current inputs.
 
void correct (const Eigen::Matrix< double, outputDim, 1 > &measurement)
 Correct the state estimate with measurement data.
 
- Public Member Functions inherited from filters::KalmanFilterBase< stateDim, inputDim >
void reset ()
 Reset the filter.
 
void reset (const Eigen::Matrix< double, stateDim, 1 > &state)
 Reset the filter.
 
void reset (const Eigen::Matrix< double, stateDim, 1 > &state, const Eigen::Matrix< double, stateDim, 1 > &stdDevs)
 Reset the filter.
 
void reset (const Eigen::Matrix< double, stateDim, 1 > &state, const Eigen::Matrix< double, stateDim, stateDim > &estCovMat)
 Reset the filter.
 
Eigen::Matrix< double, stateDim, 1 > getState () const
 Gets the current state estimate.
 
Eigen::Matrix< double, stateDim, stateDim > getEstimateCovarianceMat () const
 Get the current estimate covariance matrix.
 

Public Attributes

std::function< Eigen::Matrix< double, stateDim, stateDim >(const state_t &, const input_t &, const processnoise_t &)> stateFuncJacobianX
 Set this to provide an analytic solution to df/dx.
 
std::function< Eigen::Matrix< double, stateDim, processNoiseDim >(const state_t &, const input_t &, const processnoise_t &)> stateFuncJacobianW
 Set this to provide an analytic solution to df/dw.
 
std::function< Eigen::Matrix< double, outputDim, stateDim >(const state_t &, const outputnoise_t &)> outputFuncJacobianX
 Set this to provide an analytic solution to dh/dx.
 
std::function< Eigen::Matrix< double, outputDim, outputNoiseDim >(const state_t &, const outputnoise_t &)> outputFuncJacobianV
 Set this to provide an analytic solution to dh/dv.
 

Additional Inherited Members

- Protected Attributes inherited from filters::KalmanFilterBase< stateDim, inputDim >
Eigen::Matrix< double, stateDim, stateDim > P
 
Eigen::Matrix< double, stateDim, 1 > xHat
 

Detailed Description

template<int stateDim, int inputDim, int outputDim, int processNoiseDim, int outputNoiseDim>
class filters::ExtendedKalmanFilter< stateDim, inputDim, outputDim, processNoiseDim, outputNoiseDim >

Implements a discrete-time EKF.

This implements the more general system form described here: https://en.wikipedia.org/wiki/Extended_Kalman_filter#Non-additive_noise_formulation_and_equations

Template Parameters
stateDimThe dimension of the state space for this system. This is the number of elements in the state vector.
inputDimThe dimension of the input space for this system. This is the number of elements in the input vector.
outputDimThe dimension of the output space for this system. This is the number of elements in the output (measurement) vector.
processNoiseDimThe dimension of the process noise matrix. In systems with additive process noise, this is the same as stateDim.
outputNoiseDimThe dimension of the output noise matrix. In systems with additive output noise, this is the same as outputDim.

Member Typedef Documentation

◆ outputfunc_t

template<int stateDim, int inputDim, int outputDim, int processNoiseDim, int outputNoiseDim>
using filters::ExtendedKalmanFilter< stateDim, inputDim, outputDim, processNoiseDim, outputNoiseDim >::outputfunc_t
Initial value:
std::function<output_t(

◆ statefunc_t

template<int stateDim, int inputDim, int outputDim, int processNoiseDim, int outputNoiseDim>
using filters::ExtendedKalmanFilter< stateDim, inputDim, outputDim, processNoiseDim, outputNoiseDim >::statefunc_t
Initial value:
std::function<state_t(
const state_t&, const input_t&, const Eigen::Matrix<double, processNoiseDim, 1>&)>

Constructor & Destructor Documentation

◆ ExtendedKalmanFilter()

template<int stateDim, int inputDim, int outputDim, int processNoiseDim, int outputNoiseDim>
filters::ExtendedKalmanFilter< stateDim, inputDim, outputDim, processNoiseDim, outputNoiseDim >::ExtendedKalmanFilter ( const statefunc_t & stateFunc,
const outputfunc_t & outputFunc,
const statespace::NoiseCovMat< stateDim, processNoiseDim, inputDim > & processNoise,
const statespace::NoiseCovMat< stateDim, outputNoiseDim, outputDim > & outputNoise,
double dt )
inline

Create a new discrete-time EKF.

Parameters
stateFuncDiscrete-time state transition function. x_t+1 = f(x_t, u)
outputFuncOutput function of the system. Also known as h(x)
processNoiseThe process noise covariance matrix for this system.
outputNoiseThe output noise covariance matrix for this system.
dtThe time in seconds between updates.

Member Function Documentation

◆ correct()

template<int stateDim, int inputDim, int outputDim, int processNoiseDim, int outputNoiseDim>
void filters::ExtendedKalmanFilter< stateDim, inputDim, outputDim, processNoiseDim, outputNoiseDim >::correct ( const Eigen::Matrix< double, outputDim, 1 > & measurement)
inline

Correct the state estimate with measurement data.

The measurement should be in the same space as the state.

Parameters
measurementThe measurement to use to correct the filter.

◆ predict()

template<int stateDim, int inputDim, int outputDim, int processNoiseDim, int outputNoiseDim>
void filters::ExtendedKalmanFilter< stateDim, inputDim, outputDim, processNoiseDim, outputNoiseDim >::predict ( const Eigen::Matrix< double, inputDim, 1 > & input)
inlineoverridevirtual

Use the model to predict the next system state, given the current inputs.

Parameters
inputThe current inputs to the system.

Implements filters::KalmanFilterBase< stateDim, inputDim >.

Member Data Documentation

◆ outputFuncJacobianV

template<int stateDim, int inputDim, int outputDim, int processNoiseDim, int outputNoiseDim>
std::function<Eigen::Matrix<double, outputDim, outputNoiseDim>(const state_t&, const outputnoise_t&)> filters::ExtendedKalmanFilter< stateDim, inputDim, outputDim, processNoiseDim, outputNoiseDim >::outputFuncJacobianV

Set this to provide an analytic solution to dh/dv.

If this is null, it will be numerically approximated.

◆ outputFuncJacobianX

template<int stateDim, int inputDim, int outputDim, int processNoiseDim, int outputNoiseDim>
std::function<Eigen::Matrix<double, outputDim, stateDim>(const state_t&, const outputnoise_t&)> filters::ExtendedKalmanFilter< stateDim, inputDim, outputDim, processNoiseDim, outputNoiseDim >::outputFuncJacobianX

Set this to provide an analytic solution to dh/dx.

If this is null, it will be numerically approximated.

◆ stateFuncJacobianW

template<int stateDim, int inputDim, int outputDim, int processNoiseDim, int outputNoiseDim>
std::function<Eigen::Matrix<double, stateDim, processNoiseDim>( const state_t&, const input_t&, const processnoise_t&)> filters::ExtendedKalmanFilter< stateDim, inputDim, outputDim, processNoiseDim, outputNoiseDim >::stateFuncJacobianW

Set this to provide an analytic solution to df/dw.

If this is null, it will be numerically approximated.

◆ stateFuncJacobianX

template<int stateDim, int inputDim, int outputDim, int processNoiseDim, int outputNoiseDim>
std::function<Eigen::Matrix<double, stateDim, stateDim>(const state_t&, const input_t&, const processnoise_t&)> filters::ExtendedKalmanFilter< stateDim, inputDim, outputDim, processNoiseDim, outputNoiseDim >::stateFuncJacobianX

Set this to provide an analytic solution to df/dx.

If this is null, it will be numerically approximated.


The documentation for this class was generated from the following file: