WPILibC++ 2027.0.0-alpha-2
Loading...
Searching...
No Matches
frc::S3SigmaPoints< States > Class Template Reference

Generates sigma points and weights according to Papakonstantinou's paper[1] for the UnscentedKalmanFilter class. More...

#include <frc/estimator/S3SigmaPoints.h>

Public Member Functions

 S3SigmaPoints (double alpha=1e-3, double beta=2)
 Constructs a generator for Papakonstantinou sigma points.
 
Matrixd< States, NumSigmasSquareRootSigmaPoints (const Vectord< States > &x, const Matrixd< States, States > &S) const
 Computes the sigma points for an unscented Kalman filter given the mean (x) and square-root covariance (S) of the filter.
 
const Vectord< NumSigmas > & Wm () const
 Returns the weight for each sigma point for the mean.
 
double Wm (int i) const
 Returns an element of the weight for each sigma point for the mean.
 
const Vectord< NumSigmas > & Wc () const
 Returns the weight for each sigma point for the covariance.
 
double Wc (int i) const
 Returns an element of the weight for each sigma point for the covariance.
 

Static Public Attributes

static constexpr int NumSigmas = States + 2
 

Detailed Description

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

Generates sigma points and weights according to Papakonstantinou's paper[1] for the UnscentedKalmanFilter class.

It parameterizes the sigma points using alpha and beta terms. Unless you know better, this should be your default choice due to its high accuracy and performance.

[1] K. Papakonstantinou "A Scaled Spherical Simplex Filter (S3F) with a decreased n + 2 sigma points set size and equivalent 2n + 1 Unscented Kalman Filter (UKF) accuracy"

Template Parameters
StatesThe dimenstionality of the state. States + 2 weights will be generated.

Constructor & Destructor Documentation

◆ S3SigmaPoints()

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

Constructs a generator for Papakonstantinou 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.

Member Function Documentation

◆ SquareRootSigmaPoints()

template<int States>
Matrixd< States, NumSigmas > frc::S3SigmaPoints< States >::SquareRootSigmaPoints ( const Vectord< States > & x,
const Matrixd< States, States > & S ) const
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+1}.

◆ Wc() [1/2]

template<int States>
const Vectord< NumSigmas > & frc::S3SigmaPoints< States >::Wc ( ) const
inline

Returns the weight for each sigma point for the covariance.

◆ Wc() [2/2]

template<int States>
double frc::S3SigmaPoints< 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< NumSigmas > & frc::S3SigmaPoints< States >::Wm ( ) const
inline

Returns the weight for each sigma point for the mean.

◆ Wm() [2/2]

template<int States>
double frc::S3SigmaPoints< 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.

Member Data Documentation

◆ NumSigmas

template<int States>
int frc::S3SigmaPoints< States >::NumSigmas = States + 2
staticconstexpr

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