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. | |
int | NumSigmas () |
Returns number of sigma points for each variable in the state x. | |
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. | |
const Vectord< 2 *States+1 > & | 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< 2 *States+1 > & | 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. | |
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 Probabilistic Inference in Dynamic State-Space Models" (Doctoral dissertation)
States | The dimensionality of the state. 2 * States + 1 weights will be generated. |
|
inlineexplicit |
Constructs a generator for Van der Merwe scaled sigma points.
alpha | Determines the spread of the sigma points around the mean. Usually a small positive value (1e-3). |
beta | Incorporates prior knowledge of the distribution of the mean. For Gaussian distributions, beta = 2 is optimal. |
kappa | Secondary scaling parameter usually set to 0 or 3 - States. |
|
inline |
Returns number of sigma points for each variable in the state x.
|
inline |
Computes the sigma points for an unscented Kalman filter given the mean (x) and square-root covariance (S) of the filter.
x | An array of the means. |
S | Square-root covariance of the filter. |
|
inline |
Returns the weight for each sigma point for the covariance.
|
inline |
Returns an element of the weight for each sigma point for the covariance.
i | Element of vector to return. |
|
inline |
Returns the weight for each sigma point for the mean.
|
inline |
Returns an element of the weight for each sigma point for the mean.
i | Element of vector to return. |