Loading [MathJax]/extensions/tex2jax.js
WPILibC++ 2025.3.2
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Modules Pages Concepts
MerweScaledSigmaPoints.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <cmath>
8
9#include "frc/EigenCore.h"
10
11namespace frc {
12
13/**
14 * Generates sigma points and weights according to Van der Merwe's 2004
15 * dissertation[1] for the UnscentedKalmanFilter class.
16 *
17 * It parametrizes the sigma points using alpha, beta, kappa terms, and is the
18 * version seen in most publications. Unless you know better, this should be
19 * your default choice.
20 *
21 * [1] R. Van der Merwe "Sigma-Point Kalman Filters for Probabilistic
22 * Inference in Dynamic State-Space Models" (Doctoral dissertation)
23 *
24 * @tparam States The dimensionality of the state. 2 * States + 1 weights will
25 * be generated.
26 */
27template <int States>
29 public:
30 /**
31 * Constructs a generator for Van der Merwe scaled sigma points.
32 *
33 * @param alpha Determines the spread of the sigma points around the mean.
34 * Usually a small positive value (1e-3).
35 * @param beta Incorporates prior knowledge of the distribution of the mean.
36 * For Gaussian distributions, beta = 2 is optimal.
37 * @param kappa Secondary scaling parameter usually set to 0 or 3 - States.
38 */
39 explicit MerweScaledSigmaPoints(double alpha = 1e-3, double beta = 2,
40 int kappa = 3 - States) {
41 m_alpha = alpha;
42 m_kappa = kappa;
43
44 ComputeWeights(beta);
45 }
46
47 /**
48 * Returns number of sigma points for each variable in the state x.
49 */
50 int NumSigmas() { return 2 * States + 1; }
51
52 /**
53 * Computes the sigma points for an unscented Kalman filter given the mean
54 * (x) and square-root covariance (S) of the filter.
55 *
56 * @param x An array of the means.
57 * @param S Square-root covariance of the filter.
58 *
59 * @return Two dimensional array of sigma points. Each column contains all of
60 * the sigmas for one dimension in the problem space. Ordered by
61 * Xi_0, Xi_{1..n}, Xi_{n+1..2n}.
62 *
63 */
65 const Vectord<States>& x, const Matrixd<States, States>& S) {
66 double lambda = std::pow(m_alpha, 2) * (States + m_kappa) - States;
67 double eta = std::sqrt(lambda + States);
68 Matrixd<States, States> U = eta * S;
69
71
72 // equation (17)
73 sigmas.template block<States, 1>(0, 0) = x;
74 for (int k = 0; k < States; ++k) {
75 sigmas.template block<States, 1>(0, k + 1) =
76 x + U.template block<States, 1>(0, k);
77 sigmas.template block<States, 1>(0, States + k + 1) =
78 x - U.template block<States, 1>(0, k);
79 }
80
81 return sigmas;
82 }
83
84 /**
85 * Returns the weight for each sigma point for the mean.
86 */
87 const Vectord<2 * States + 1>& Wm() const { return m_Wm; }
88
89 /**
90 * Returns an element of the weight for each sigma point for the mean.
91 *
92 * @param i Element of vector to return.
93 */
94 double Wm(int i) const { return m_Wm(i, 0); }
95
96 /**
97 * Returns the weight for each sigma point for the covariance.
98 */
99 const Vectord<2 * States + 1>& Wc() const { return m_Wc; }
100
101 /**
102 * Returns an element of the weight for each sigma point for the covariance.
103 *
104 * @param i Element of vector to return.
105 */
106 double Wc(int i) const { return m_Wc(i, 0); }
107
108 private:
111 double m_alpha;
112 int m_kappa;
113
114 /**
115 * Computes the weights for the scaled unscented Kalman filter.
116 *
117 * @param beta Incorporates prior knowledge of the distribution of the mean.
118 */
119 void ComputeWeights(double beta) {
120 double lambda = std::pow(m_alpha, 2) * (States + m_kappa) - States;
121
122 double c = 0.5 / (States + lambda);
125
126 m_Wm(0) = lambda / (States + lambda);
127 m_Wc(0) = lambda / (States + lambda) + (1 - std::pow(m_alpha, 2) + beta);
128 }
129};
130
131} // namespace frc
Generates sigma points and weights according to Van der Merwe's 2004 dissertation[1] for the Unscente...
Definition MerweScaledSigmaPoints.h:28
int NumSigmas()
Returns number of sigma points for each variable in the state x.
Definition MerweScaledSigmaPoints.h:50
MerweScaledSigmaPoints(double alpha=1e-3, double beta=2, int kappa=3 - States)
Constructs a generator for Van der Merwe scaled sigma points.
Definition MerweScaledSigmaPoints.h:39
double Wc(int i) const
Returns an element of the weight for each sigma point for the covariance.
Definition MerweScaledSigmaPoints.h:106
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 covarianc...
Definition MerweScaledSigmaPoints.h:64
double Wm(int i) const
Returns an element of the weight for each sigma point for the mean.
Definition MerweScaledSigmaPoints.h:94
const Vectord< 2 *States+1 > & Wm() const
Returns the weight for each sigma point for the mean.
Definition MerweScaledSigmaPoints.h:87
const Vectord< 2 *States+1 > & Wc() const
Returns the weight for each sigma point for the covariance.
Definition MerweScaledSigmaPoints.h:99
Definition CAN.h:11
Eigen::Matrix< double, Rows, Cols, Options, MaxRows, MaxCols > Matrixd
Definition EigenCore.h:21
Eigen::Vector< double, Size > Vectord
Definition EigenCore.h:12
#define S(label, offset, message)
Definition Errors.h:113