WPILibC++ 2023.4.3
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 <tuple>
8
9#include "Eigen/QR"
10#include "frc/EigenCore.h"
11
12namespace frc {
13
14/**
15 * Computes unscented transform of a set of sigma points and weights. CovDim
16 * returns the mean and square-root covariance of the sigma points in a tuple.
17 *
18 * This works in conjunction with the UnscentedKalmanFilter class. For use with
19 * square-root form UKFs.
20 *
21 * @tparam CovDim Dimension of covariance of sigma points after passing
22 * through the transform.
23 * @tparam States Number of states.
24 * @param sigmas List of sigma points.
25 * @param Wm Weights for the mean.
26 * @param Wc Weights for the covariance.
27 * @param meanFunc A function that computes the mean of 2 * States + 1 state
28 * vectors using a given set of weights.
29 * @param residualFunc A function that computes the residual of two state
30 * vectors (i.e. it subtracts them.)
31 * @param squareRootR Square-root of the noise covaraince of the sigma points.
32 *
33 * @return Tuple of x, mean of sigma points; S, square-root covariance of
34 * sigmas.
35 */
36template <int CovDim, int States>
37std::tuple<Vectord<CovDim>, Matrixd<CovDim, CovDim>>
43 meanFunc,
44 std::function<Vectord<CovDim>(const Vectord<CovDim>&,
45 const Vectord<CovDim>&)>
46 residualFunc,
47 const Matrixd<CovDim, CovDim>& squareRootR) {
48 // New mean is usually just the sum of the sigmas * weight:
49 // n
50 // dot = Σ W[k] Xᵢ[k]
51 // k=1
52 Vectord<CovDim> x = meanFunc(sigmas, Wm);
53
55 for (int i = 0; i < States * 2; i++) {
56 Sbar.template block<CovDim, 1>(0, i) =
57 std::sqrt(Wc[1]) *
58 residualFunc(sigmas.template block<CovDim, 1>(0, 1 + i), x);
59 }
60 Sbar.template block<CovDim, CovDim>(0, States * 2) = squareRootR;
61
62 // Merwe defines the QR decomposition as Aᵀ = QR
63 Matrixd<CovDim, CovDim> S = Sbar.transpose()
64 .householderQr()
65 .matrixQR()
66 .template block<CovDim, CovDim>(0, 0)
67 .template triangularView<Eigen::Upper>();
68
70 S, residualFunc(sigmas.template block<CovDim, 1>(0, 0), x), Wc[0]);
71
72 return std::make_tuple(x, S);
73}
74
75} // namespace frc
The matrix class, also used for vectors and row-vectors.
Definition: Matrix.h:180
auto sqrt(const UnitType &value) noexcept -> unit_t< square_root< typename units::traits::unit_t_traits< UnitType >::unit_type >, typename units::traits::unit_t_traits< UnitType >::underlying_type, linear_scale >
computes the square root of value
Definition: math.h:483
Definition: AprilTagFieldLayout.h:22
std::tuple< Vectord< CovDim >, Matrixd< CovDim, CovDim > > SquareRootUnscentedTransform(const Matrixd< CovDim, 2 *States+1 > &sigmas, const Vectord< 2 *States+1 > &Wm, const Vectord< 2 *States+1 > &Wc, std::function< Vectord< CovDim >(const Matrixd< CovDim, 2 *States+1 > &, const Vectord< 2 *States+1 > &)> 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:38
Eigen::Vector< double, Size > Vectord
Definition: EigenCore.h:12
Definition: LLT.h:237
#define S(label, offset, message)
Definition: Errors.h:118