Generates sigma points and weights according to Papakonstantinou's paper[1] for the UnscentedKalmanFilter class.
More...
|
| S3SigmaPoints (double alpha=1e-3, double beta=2) |
| Constructs a generator for Papakonstantinou sigma points.
|
|
Matrixd< States, NumSigmas > | SquareRootSigmaPoints (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.
|
|
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
-
States | The dimenstionality of the state. States + 2 weights will be generated. |