WPILibC++ 2027.0.0-alpha-2
Loading...
Searching...
No Matches
S3SigmaPoints.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 <wpi/array.h>
8
9#include "frc/EigenCore.h"
11
12namespace frc {
13
14/**
15 * Generates sigma points and weights according to Papakonstantinou's paper[1]
16 * for the UnscentedKalmanFilter class.
17 *
18 * It parameterizes the sigma points using alpha and beta terms. Unless you know
19 * better, this should be your default choice due to its high accuracy and
20 * performance.
21 *
22 * [1] K. Papakonstantinou "A Scaled Spherical Simplex Filter (S3F) with a
23 * decreased n + 2 sigma points set size and equivalent 2n + 1 Unscented Kalman
24 * Filter (UKF) accuracy"
25 *
26 * @tparam States The dimenstionality of the state. States + 2 weights will be
27 * generated.
28 */
29template <int States>
31 public:
32 static constexpr int NumSigmas = States + 2;
33
34 /**
35 * Constructs a generator for Papakonstantinou sigma points.
36 *
37 * @param alpha Determines the spread of the sigma points around the mean.
38 * Usually a small positive value (1e-3).
39 * @param beta Incorporates prior knowledge of the distribution of the mean.
40 * For Gaussian distributions, beta = 2 is optimal.
41 */
42 explicit S3SigmaPoints(double alpha = 1e-3, double beta = 2)
43 : m_alpha{alpha} {
44 ComputeWeights(beta);
45 }
46
47 /**
48 * Computes the sigma points for an unscented Kalman filter given the mean (x)
49 * and square-root covariance (S) of the filter.
50 *
51 * @param x An array of the means.
52 * @param S Square-root covariance of the filter.
53 *
54 * @return Two dimensional array of sigma points. Each column contains all of
55 * the sigmas for one dimension in the problem space. Ordered by Xi_0,
56 * Xi_{1..n+1}.
57 */
59 const Vectord<States>& x, const Matrixd<States, States>& S) const {
60 // table (1), equation (12)
62 for (size_t t = 1; t <= States; ++t) {
63 q[t - 1] = m_alpha * std::sqrt(static_cast<double>(t * (States + 1)) /
64 static_cast<double>(t + 1));
65 }
66
68 C.template block<States, 1>(0, 0) = Vectord<States>::Constant(0.0);
69 for (int col = 1; col < NumSigmas; ++col) {
70 for (int row = 0; row < States; ++row) {
71 if (row < col - 2) {
72 C(row, col) = 0.0;
73 } else if (row == col - 2) {
74 C(row, col) = q[row];
75 } else {
76 C(row, col) = -q[row] / (row + 1);
77 }
78 }
79 }
80
82 for (int col = 0; col < NumSigmas; ++col) {
83 sigmas.col(col) = x + S * C.col(col);
84 }
85
86 return sigmas;
87 }
88
89 /**
90 * Returns the weight for each sigma point for the mean.
91 */
92 const Vectord<NumSigmas>& Wm() const { return m_Wm; }
93
94 /**
95 * Returns an element of the weight for each sigma point for the mean.
96 *
97 * @param i Element of vector to return.
98 */
99 double Wm(int i) const { return m_Wm(i, 0); }
100
101 /**
102 * Returns the weight for each sigma point for the covariance.
103 */
104 const Vectord<NumSigmas>& Wc() const { return m_Wc; }
105
106 /**
107 * Returns an element of the weight for each sigma point for the covariance.
108 *
109 * @param i Element of vector to return.
110 */
111 double Wc(int i) const { return m_Wc(i, 0); }
112
113 private:
116 double m_alpha;
117
118 /**
119 * Computes the weights for the scaled unscented Kalman filter.
120 *
121 * @param beta Incorporates prior knowledge of the distribution of the mean.
122 */
123 void ComputeWeights(double beta) {
124 double alpha_sq = m_alpha * m_alpha;
125
126 double c = 1.0 / (alpha_sq * (States + 1));
129
130 m_Wm(0) = 1.0 - 1.0 / alpha_sq;
131 m_Wc(0) = 1.0 - 1.0 / alpha_sq + (1 - alpha_sq + beta);
132 }
133};
134
135} // namespace frc
Generates sigma points and weights according to Papakonstantinou's paper[1] for the UnscentedKalmanFi...
Definition S3SigmaPoints.h:30
const Vectord< NumSigmas > & Wm() const
Returns the weight for each sigma point for the mean.
Definition S3SigmaPoints.h:92
double Wm(int i) const
Returns an element of the weight for each sigma point for the mean.
Definition S3SigmaPoints.h:99
const Vectord< NumSigmas > & Wc() const
Returns the weight for each sigma point for the covariance.
Definition S3SigmaPoints.h:104
static constexpr int NumSigmas
Definition S3SigmaPoints.h:32
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 covarianc...
Definition S3SigmaPoints.h:58
double Wc(int i) const
Returns an element of the weight for each sigma point for the covariance.
Definition S3SigmaPoints.h:111
S3SigmaPoints(double alpha=1e-3, double beta=2)
Constructs a generator for Papakonstantinou sigma points.
Definition S3SigmaPoints.h:42
This class is a wrapper around std::array that does compile time size checking.
Definition array.h:26
Definition SystemServer.h:9
Eigen::Matrix< double, Rows, Cols, Options, MaxRows, MaxCols > Matrixd
Definition EigenCore.h:21
Eigen::Vector< double, Size > Vectord
Definition EigenCore.h:12
constexpr empty_array_t empty_array
Definition array.h:16
#define S(label, offset, message)
Definition Errors.h:113