40 int kappa = 3 - States) {
66 double lambda = std::pow(m_alpha, 2) * (States + m_kappa) - States;
67 double eta = std::sqrt(lambda + States);
71 sigmas.template block<States, 1>(0, 0) = x;
72 for (
int k = 0; k < States; ++k) {
73 sigmas.template block<States, 1>(0, k + 1) =
74 x + U.template block<States, 1>(0, k);
75 sigmas.template block<States, 1>(0, States + k + 1) =
76 x - U.template block<States, 1>(0, k);
92 double Wm(
int i)
const {
return m_Wm(i, 0); }
104 double Wc(
int i)
const {
return m_Wc(i, 0); }
117 void ComputeWeights(
double beta) {
118 double lambda = std::pow(m_alpha, 2) * (States + m_kappa) - States;
120 double c = 0.5 / (States + lambda);
124 m_Wm(0) = lambda / (States + lambda);
125 m_Wc(0) = lambda / (States + lambda) + (1 - std::pow(m_alpha, 2) + beta);
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:104
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:92
const Vectord< 2 *States+1 > & Wm() const
Returns the weight for each sigma point for the mean.
Definition MerweScaledSigmaPoints.h:85
const Vectord< 2 *States+1 > & Wc() const
Returns the weight for each sigma point for the covariance.
Definition MerweScaledSigmaPoints.h:97
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