WPILibC++ 2027.0.0-alpha-2
Loading...
Searching...
No Matches
UnscentedTransform.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 <functional>
8#include <tuple>
9
10#include <Eigen/QR>
11
12#include "frc/EigenCore.h"
13
14namespace frc {
15
16/**
17 * Computes unscented transform of a set of sigma points and weights. CovDim
18 * returns the mean and square-root covariance of the sigma points in a tuple.
19 *
20 * This works in conjunction with the UnscentedKalmanFilter class. For use with
21 * square-root form UKFs.
22 *
23 * @tparam CovDim Dimension of covariance of sigma points after passing
24 * through the transform.
25 * @tparam NumSigmas Number of sigma points.
26 * @param sigmas List of sigma points.
27 * @param Wm Weights for the mean.
28 * @param Wc Weights for the covariance.
29 * @param meanFunc A function that computes the mean of NumSigmas state
30 * vectors using a given set of weights.
31 * @param residualFunc A function that computes the residual of two state
32 * vectors (i.e. it subtracts them.)
33 * @param squareRootR Square-root of the noise covariance of the sigma points.
34 *
35 * @return Tuple of x, mean of sigma points; S, square-root covariance of
36 * sigmas.
37 */
38template <int CovDim, int NumSigmas>
39std::tuple<Vectord<CovDim>, Matrixd<CovDim, CovDim>>
41 const Matrixd<CovDim, NumSigmas>& sigmas, const Vectord<NumSigmas>& Wm,
42 const Vectord<NumSigmas>& Wc,
44 const Vectord<NumSigmas>&)>
45 meanFunc,
46 std::function<Vectord<CovDim>(const Vectord<CovDim>&,
47 const Vectord<CovDim>&)>
48 residualFunc,
49 const Matrixd<CovDim, CovDim>& squareRootR) {
50 // New mean is usually just the sum of the sigmas * weights:
51 //
52 // 2n
53 // x̂ = Σ Wᵢ⁽ᵐ⁾𝒳ᵢ
54 // i=0
55 //
56 // equations (19) and (23) in the paper show this,
57 // but we allow a custom function, usually for angle wrapping
58 Vectord<CovDim> x = meanFunc(sigmas, Wm);
59
60 // Form an intermediate matrix S⁻ as:
61 //
62 // [√{W₁⁽ᶜ⁾}(𝒳_{1:2L} - x̂) √{Rᵛ}]
63 //
64 // the part of equations (20) and (24) within the "qr{}"
65 //
66 // Note that we allow a custom function instead of the difference to allow
67 // angle wrapping. Furthermore, we allow an arbitrary number of sigma points
68 // to support similar methods such as the Scaled Spherical Simplex Filter
69 // (S3F).
70 Matrixd<CovDim, NumSigmas - 1 + CovDim> Sbar;
71 for (int i = 0; i < NumSigmas - 1; i++) {
72 Sbar.template block<CovDim, 1>(0, i) =
73 std::sqrt(Wc[1]) *
74 residualFunc(sigmas.template block<CovDim, 1>(0, 1 + i), x);
75 }
76 Sbar.template block<CovDim, CovDim>(0, NumSigmas - 1) = squareRootR;
77
78 // Compute the square-root covariance of the sigma points.
79 //
80 // We transpose S⁻ first because we formed it by horizontally
81 // concatenating each part; it should be vertical so we can take
82 // the QR decomposition as defined in the "QR Decomposition" passage
83 // of section 3. "EFFICIENT SQUARE-ROOT IMPLEMENTATION"
84 //
85 // The resulting matrix R is the square-root covariance S, but it
86 // is upper triangular, so we need to transpose it.
87 //
88 // equations (20) and (24)
89 Matrixd<CovDim, CovDim> S = Sbar.transpose()
90 .householderQr()
91 .matrixQR()
92 .template block<CovDim, CovDim>(0, 0)
93 .template triangularView<Eigen::Upper>()
94 .transpose();
95
96 // Update or downdate the square-root covariance with (𝒳₀-x̂)
97 // depending on whether its weight (W₀⁽ᶜ⁾) is positive or negative.
98 //
99 // equations (21) and (25)
100 Eigen::internal::llt_inplace<double, Eigen::Lower>::rankUpdate(
101 S, residualFunc(sigmas.template block<CovDim, 1>(0, 0), x), Wc[0]);
102
103 return std::make_tuple(x, S);
104}
105
106} // namespace frc
Definition SystemServer.h:9
std::tuple< Vectord< CovDim >, Matrixd< CovDim, CovDim > > SquareRootUnscentedTransform(const Matrixd< CovDim, NumSigmas > &sigmas, const Vectord< NumSigmas > &Wm, const Vectord< NumSigmas > &Wc, std::function< Vectord< CovDim >(const Matrixd< CovDim, NumSigmas > &, const Vectord< NumSigmas > &)> meanFunc, std::function< Vectord< CovDim >(const Vectord< CovDim > &, const Vectord< CovDim > &)> residualFunc, const Matrixd< CovDim, CovDim > &squareRootR)
Computes unscented transform of a set of sigma points and weights.
Definition UnscentedTransform.h:40
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