RIT VEXU Core API
|
#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 |
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
STATES | the dimension of the state. NUM_SIGMAS sigma points and weights will be generated. |
|
inline |
Constructs a sigma point generator for Spherical Simplex sigma points
alpha | Determines the spread of the sigma points around the mean. Smaller values are closer to the mean, this is usually a small value. |
beta | Incorporates prior knowledge of the distribution of the state. For Gaussian distributions, beta = 2 is optimal. |
|
inline |
Returns the number of sigma points, for simplex sigma points this is N+2.
|
inline |
Computes the sigma points given a mean (x) and square-root covariance (S).
x | Vector of the means. |
S | Square-root covariance. |
|
inline |
Returns a vector containing the weights of each sigma point for the covariance.
|
inline |
Returns the weight for the i-th sigma point for the covariance.
i | Element of the weights vector to return. |
|
inline |
Returns a vector containing the weights of each sigma point for the mean.
|
inline |
Returns the weight for the i-th sigma point for the mean.
i | Element of the weights vector to return. |