WPILibC++ 2024.3.2
frc::MerweScaledSigmaPoints< States > Class Template Reference

Generates sigma points and weights according to Van der Merwe's 2004 dissertation[1] for the UnscentedKalmanFilter class. More...

#include <frc/estimator/MerweScaledSigmaPoints.h>

Public Member Functions

 MerweScaledSigmaPoints (double alpha=1e-3, double beta=2, int kappa=3 - States)
 Constructs a generator for Van der Merwe scaled sigma points. More...
 
int NumSigmas ()
 Returns number of sigma points for each variable in the state x. More...
 
Matrixd< States, 2 *States+1 > SquareRootSigmaPoints (const Vectord< States > &x, const Matrixd< States, States > &S)
 Computes the sigma points for an unscented Kalman filter given the mean (x) and square-root covariance(S) of the filter. More...
 
const Vectord< 2 *States+1 > & Wm () const
 Returns the weight for each sigma point for the mean. More...
 
double Wm (int i) const
 Returns an element of the weight for each sigma point for the mean. More...
 
const Vectord< 2 *States+1 > & Wc () const
 Returns the weight for each sigma point for the covariance. More...
 
double Wc (int i) const
 Returns an element of the weight for each sigma point for the covariance. More...
 

Detailed Description

template<int States>
class frc::MerweScaledSigmaPoints< States >

Generates sigma points and weights according to Van der Merwe's 2004 dissertation[1] for the UnscentedKalmanFilter class.

It parametrizes the sigma points using alpha, beta, kappa terms, and is the version seen in most publications. Unless you know better, this should be your default choice.

[1] R. Van der Merwe "Sigma-Point Kalman Filters for Probabilitic Inference in Dynamic State-Space Models" (Doctoral dissertation)

Template Parameters
StatesThe dimensionality of the state. 2 * States + 1 weights will be generated.

Constructor & Destructor Documentation

◆ MerweScaledSigmaPoints()

template<int States>
frc::MerweScaledSigmaPoints< States >::MerweScaledSigmaPoints ( double  alpha = 1e-3,
double  beta = 2,
int  kappa = 3 - States 
)
inlineexplicit

Constructs a generator for Van der Merwe scaled sigma points.

Parameters
alphaDetermines the spread of the sigma points around the mean. Usually a small positive value (1e-3).
betaIncorporates prior knowledge of the distribution of the mean. For Gaussian distributions, beta = 2 is optimal.
kappaSecondary scaling parameter usually set to 0 or 3 - States.

Member Function Documentation

◆ NumSigmas()

template<int States>
int frc::MerweScaledSigmaPoints< States >::NumSigmas ( )
inline

Returns number of sigma points for each variable in the state x.

◆ SquareRootSigmaPoints()

template<int States>
Matrixd< States, 2 *States+1 > frc::MerweScaledSigmaPoints< States >::SquareRootSigmaPoints ( const Vectord< States > &  x,
const Matrixd< States, States > &  S 
)
inline

Computes the sigma points for an unscented Kalman filter given the mean (x) and square-root covariance(S) of the filter.

Parameters
xAn array of the means.
SSquare-root covariance of the filter.
Returns
Two dimensional array of sigma points. Each column contains all of the sigmas for one dimension in the problem space. Ordered by Xi_0, Xi_{1..n}, Xi_{n+1..2n}.

◆ Wc() [1/2]

template<int States>
const Vectord< 2 *States+1 > & frc::MerweScaledSigmaPoints< States >::Wc ( ) const
inline

Returns the weight for each sigma point for the covariance.

◆ Wc() [2/2]

template<int States>
double frc::MerweScaledSigmaPoints< States >::Wc ( int  i) const
inline

Returns an element of the weight for each sigma point for the covariance.

Parameters
iElement of vector to return.

◆ Wm() [1/2]

template<int States>
const Vectord< 2 *States+1 > & frc::MerweScaledSigmaPoints< States >::Wm ( ) const
inline

Returns the weight for each sigma point for the mean.

◆ Wm() [2/2]

template<int States>
double frc::MerweScaledSigmaPoints< States >::Wm ( int  i) const
inline

Returns an element of the weight for each sigma point for the mean.

Parameters
iElement of vector to return.

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