RIT VEXU Core API
Loading...
Searching...
No Matches
ScaledSphericalSimplexSigmaPoints< STATES > Class Template Reference

#include <unscented_kalman_filter.h>

Public Member Functions

 ScaledSphericalSimplexSigmaPoints (double alpha=0.001, double beta=2)
 
int num_sigmas ()
 
EMat< STATES, NUM_SIGMAS > square_root_sigma_points (const EVec< STATES > &x, const EMat< STATES, STATES > &S)
 
const EVec< NUM_SIGMAS > & Wm () const
 
const EVec< NUM_SIGMAS > & Wc () const
 
double Wm (int i) const
 
double Wc (int i) const
 

Detailed Description

template<int STATES>
class ScaledSphericalSimplexSigmaPoints< STATES >

Generates sigma points and weights according to the paper [1] This is very different from Wan and Merwe's formulation.

This only requires N + 2 sigma points instead of 2N + 1 sigma points. Rather than generating sigma points symmetrically around the mean, it generates them as vertices of an N-simplex.

The performance of the filter using this reduced set of sigma points is identical to the standard method, so there is no downside to using it here.

[1] 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 dimension of the state. NUM_SIGMAS sigma points and weights will be generated.

Constructor & Destructor Documentation

◆ ScaledSphericalSimplexSigmaPoints()

template<int STATES>
ScaledSphericalSimplexSigmaPoints< STATES >::ScaledSphericalSimplexSigmaPoints ( double alpha = 0.001,
double beta = 2 )
inline

Constructs a sigma point generator for Spherical Simplex sigma points

Parameters
alphaDetermines the spread of the sigma points around the mean. Smaller values are closer to the mean, this is usually a small value.
betaIncorporates prior knowledge of the distribution of the state. For Gaussian distributions, beta = 2 is optimal.

Member Function Documentation

◆ num_sigmas()

template<int STATES>
int ScaledSphericalSimplexSigmaPoints< STATES >::num_sigmas ( )
inline

Returns the number of sigma points, for simplex sigma points this is N+2.

◆ square_root_sigma_points()

template<int STATES>
EMat< STATES, NUM_SIGMAS > ScaledSphericalSimplexSigmaPoints< STATES >::square_root_sigma_points ( const EVec< STATES > & x,
const EMat< STATES, STATES > & S )
inline

Computes the sigma points given a mean (x) and square-root covariance (S).

Parameters
xVector of the means.
SSquare-root covariance.
Returns
Matrix containing the sigma points. Each column contains one sigma point in the same space as x. The first column is the same as the mean, with the others arranged around the mean.

◆ Wc() [1/2]

template<int STATES>
const EVec< NUM_SIGMAS > & ScaledSphericalSimplexSigmaPoints< STATES >::Wc ( ) const
inline

Returns a vector containing the weights of each sigma point for the covariance.

◆ Wc() [2/2]

template<int STATES>
double ScaledSphericalSimplexSigmaPoints< STATES >::Wc ( int i) const
inline

Returns the weight for the i-th sigma point for the covariance.

Parameters
iElement of the weights vector to return.

◆ Wm() [1/2]

template<int STATES>
const EVec< NUM_SIGMAS > & ScaledSphericalSimplexSigmaPoints< STATES >::Wm ( ) const
inline

Returns a vector containing the weights of each sigma point for the mean.

◆ Wm() [2/2]

template<int STATES>
double ScaledSphericalSimplexSigmaPoints< STATES >::Wm ( int i) const
inline

Returns the weight for the i-th sigma point for the mean.

Parameters
iElement of the weights vector to return.

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