WPILibC++ 2023.4.3-108-ge5452e3
StateSpaceUtil.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 <array>
8#include <cmath>
9#include <concepts>
10#include <limits>
11#include <random>
12
13#include <wpi/SymbolExports.h>
14#include <wpi/deprecated.h>
15
16#include "Eigen/Eigenvalues"
17#include "Eigen/QR"
18#include "frc/EigenCore.h"
19#include "frc/geometry/Pose2d.h"
20
21namespace frc {
22namespace detail {
23
24template <typename Matrix, typename T, typename... Ts>
25void CostMatrixImpl(Matrix& result, T elem, Ts... elems) {
26 if (elem == std::numeric_limits<double>::infinity()) {
27 result(result.rows() - (sizeof...(Ts) + 1)) = 0.0;
28 } else {
29 result(result.rows() - (sizeof...(Ts) + 1)) = 1.0 / std::pow(elem, 2);
30 }
31 if constexpr (sizeof...(Ts) > 0) {
32 CostMatrixImpl(result, elems...);
33 }
34}
35
36template <typename Matrix, typename T, typename... Ts>
37void CovMatrixImpl(Matrix& result, T elem, Ts... elems) {
38 result(result.rows() - (sizeof...(Ts) + 1)) = std::pow(elem, 2);
39 if constexpr (sizeof...(Ts) > 0) {
40 CovMatrixImpl(result, elems...);
41 }
42}
43
44template <typename Matrix, typename T, typename... Ts>
45void WhiteNoiseVectorImpl(Matrix& result, T elem, Ts... elems) {
46 std::random_device rd;
47 std::mt19937 gen{rd()};
48 std::normal_distribution<> distr{0.0, elem};
49
50 result(result.rows() - (sizeof...(Ts) + 1)) = distr(gen);
51 if constexpr (sizeof...(Ts) > 0) {
53 }
54}
55
56template <int States, int Inputs>
58 const Matrixd<States, Inputs>& B) {
60
61 for (int i = 0; i < States; ++i) {
62 if (es.eigenvalues()[i].real() * es.eigenvalues()[i].real() +
63 es.eigenvalues()[i].imag() * es.eigenvalues()[i].imag() <
64 1) {
65 continue;
66 }
67
68 Eigen::Matrix<std::complex<double>, States, States + Inputs> E;
69 E << es.eigenvalues()[i] * Eigen::Matrix<std::complex<double>, States,
70 States>::Identity() -
71 A,
72 B;
73
75 Eigen::Matrix<std::complex<double>, States, States + Inputs>>
76 qr{E};
77 if (qr.rank() < States) {
78 return false;
79 }
80 }
81 return true;
82}
83
84} // namespace detail
85
86/**
87 * Creates a cost matrix from the given vector for use with LQR.
88 *
89 * The cost matrix is constructed using Bryson's rule. The inverse square of
90 * each tolerance is placed on the cost matrix diagonal. If a tolerance is
91 * infinity, its cost matrix entry is set to zero.
92 *
93 * @param tolerances An array. For a Q matrix, its elements are the maximum
94 * allowed excursions of the states from the reference. For an
95 * R matrix, its elements are the maximum allowed excursions
96 * of the control inputs from no actuation.
97 * @return State excursion or control effort cost matrix.
98 */
99template <std::same_as<double>... Ts>
100Matrixd<sizeof...(Ts), sizeof...(Ts)> MakeCostMatrix(Ts... tolerances) {
101 Eigen::DiagonalMatrix<double, sizeof...(Ts)> result;
102 detail::CostMatrixImpl(result.diagonal(), tolerances...);
103 return result;
104}
105
106/**
107 * Creates a covariance matrix from the given vector for use with Kalman
108 * filters.
109 *
110 * Each element is squared and placed on the covariance matrix diagonal.
111 *
112 * @param stdDevs An array. For a Q matrix, its elements are the standard
113 * deviations of each state from how the model behaves. For an R
114 * matrix, its elements are the standard deviations for each
115 * output measurement.
116 * @return Process noise or measurement noise covariance matrix.
117 */
118template <std::same_as<double>... Ts>
119Matrixd<sizeof...(Ts), sizeof...(Ts)> MakeCovMatrix(Ts... stdDevs) {
120 Eigen::DiagonalMatrix<double, sizeof...(Ts)> result;
121 detail::CovMatrixImpl(result.diagonal(), stdDevs...);
122 return result;
123}
124
125/**
126 * Creates a cost matrix from the given vector for use with LQR.
127 *
128 * The cost matrix is constructed using Bryson's rule. The inverse square of
129 * each element in the input is placed on the cost matrix diagonal. If a
130 * tolerance is infinity, its cost matrix entry is set to zero.
131 *
132 * @param costs An array. For a Q matrix, its elements are the maximum allowed
133 * excursions of the states from the reference. For an R matrix,
134 * its elements are the maximum allowed excursions of the control
135 * inputs from no actuation.
136 * @return State excursion or control effort cost matrix.
137 */
138template <size_t N>
139Matrixd<N, N> MakeCostMatrix(const std::array<double, N>& costs) {
141 auto& diag = result.diagonal();
142 for (size_t i = 0; i < N; ++i) {
143 if (costs[i] == std::numeric_limits<double>::infinity()) {
144 diag(i) = 0.0;
145 } else {
146 diag(i) = 1.0 / std::pow(costs[i], 2);
147 }
148 }
149 return result;
150}
151
152/**
153 * Creates a covariance matrix from the given vector for use with Kalman
154 * filters.
155 *
156 * Each element is squared and placed on the covariance matrix diagonal.
157 *
158 * @param stdDevs An array. For a Q matrix, its elements are the standard
159 * deviations of each state from how the model behaves. For an R
160 * matrix, its elements are the standard deviations for each
161 * output measurement.
162 * @return Process noise or measurement noise covariance matrix.
163 */
164template <size_t N>
165Matrixd<N, N> MakeCovMatrix(const std::array<double, N>& stdDevs) {
167 auto& diag = result.diagonal();
168 for (size_t i = 0; i < N; ++i) {
169 diag(i) = std::pow(stdDevs[i], 2);
170 }
171 return result;
172}
173
174template <std::same_as<double>... Ts>
175Matrixd<sizeof...(Ts), 1> MakeWhiteNoiseVector(Ts... stdDevs) {
176 Matrixd<sizeof...(Ts), 1> result;
178 return result;
179}
180
181/**
182 * Creates a vector of normally distributed white noise with the given noise
183 * intensities for each element.
184 *
185 * @param stdDevs An array whose elements are the standard deviations of each
186 * element of the noise vector.
187 * @return White noise vector.
188 */
189template <int N>
190Vectord<N> MakeWhiteNoiseVector(const std::array<double, N>& stdDevs) {
191 std::random_device rd;
192 std::mt19937 gen{rd()};
193
195 for (int i = 0; i < N; ++i) {
196 // Passing a standard deviation of 0.0 to std::normal_distribution is
197 // undefined behavior
198 if (stdDevs[i] == 0.0) {
199 result(i) = 0.0;
200 } else {
201 std::normal_distribution distr{0.0, stdDevs[i]};
202 result(i) = distr(gen);
203 }
204 }
205 return result;
206}
207
208/**
209 * Converts a Pose2d into a vector of [x, y, theta].
210 *
211 * @param pose The pose that is being represented.
212 *
213 * @return The vector.
214 */
217
218/**
219 * Converts a Pose2d into a vector of [x, y, std::cos(theta), std::sin(theta)].
220 *
221 * @param pose The pose that is being represented.
222 *
223 * @return The vector.
224 */
227
228/**
229 * Returns true if (A, B) is a stabilizable pair.
230 *
231 * (A, B) is stabilizable if and only if the uncontrollable eigenvalues of A, if
232 * any, have absolute values less than one, where an eigenvalue is
233 * uncontrollable if rank([λI - A, B]) < n where n is the number of states.
234 *
235 * @tparam States The number of states.
236 * @tparam Inputs The number of inputs.
237 * @param A System matrix.
238 * @param B Input matrix.
239 */
240template <int States, int Inputs>
242 const Matrixd<States, Inputs>& B) {
243 return detail::IsStabilizableImpl<States, Inputs>(A, B);
244}
245
246/**
247 * Returns true if (A, C) is a detectable pair.
248 *
249 * (A, C) is detectable if and only if the unobservable eigenvalues of A, if
250 * any, have absolute values less than one, where an eigenvalue is unobservable
251 * if rank([λI - A; C]) < n where n is the number of states.
252 *
253 * @tparam States The number of states.
254 * @tparam Outputs The number of outputs.
255 * @param A System matrix.
256 * @param C Output matrix.
257 */
258template <int States, int Outputs>
260 const Matrixd<Outputs, States>& C) {
261 return detail::IsStabilizableImpl<States, Outputs>(A.transpose(),
262 C.transpose());
263}
264
265// Template specializations are used here to make common state-input pairs
266// compile faster.
267template <>
269 const Matrixd<1, 1>& B);
270
271// Template specializations are used here to make common state-input pairs
272// compile faster.
273template <>
275 const Matrixd<2, 1>& B);
276
277/**
278 * Converts a Pose2d into a vector of [x, y, theta].
279 *
280 * @param pose The pose that is being represented.
281 *
282 * @return The vector.
283 */
286
287/**
288 * Clamps input vector between system's minimum and maximum allowable input.
289 *
290 * @tparam Inputs The number of inputs.
291 * @param u Input vector to clamp.
292 * @param umin The minimum input magnitude.
293 * @param umax The maximum input magnitude.
294 * @return Clamped input vector.
295 */
296template <int Inputs>
298 const Vectord<Inputs>& umin,
299 const Vectord<Inputs>& umax) {
301 for (int i = 0; i < Inputs; ++i) {
302 result(i) = std::clamp(u(i), umin(i), umax(i));
303 }
304 return result;
305}
306
307/**
308 * Renormalize all inputs if any exceeds the maximum magnitude. Useful for
309 * systems such as differential drivetrains.
310 *
311 * @tparam Inputs The number of inputs.
312 * @param u The input vector.
313 * @param maxMagnitude The maximum magnitude any input can have.
314 * @return The normalizedInput
315 */
316template <int Inputs>
318 double maxMagnitude) {
319 double maxValue = u.template lpNorm<Eigen::Infinity>();
320
321 if (maxValue > maxMagnitude) {
322 return u * maxMagnitude / maxValue;
323 }
324 return u;
325}
326} // namespace frc
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Householder rank-revealing QR decomposition of a matrix with column-pivoting.
Definition: ColPivHouseholderQR.h:53
Represents a diagonal matrix with its storage.
Definition: DiagonalMatrix.h:142
\eigenvalues_module
Definition: EigenSolver.h:65
The matrix class, also used for vectors and row-vectors.
Definition: Matrix.h:180
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:25
Definition: format-inl.h:32
result
Definition: format.h:2564
void CostMatrixImpl(Matrix &result, T elem, Ts... elems)
Definition: StateSpaceUtil.h:25
void WhiteNoiseVectorImpl(Matrix &result, T elem, Ts... elems)
Definition: StateSpaceUtil.h:45
void CovMatrixImpl(Matrix &result, T elem, Ts... elems)
Definition: StateSpaceUtil.h:37
bool IsStabilizableImpl(const Matrixd< States, States > &A, const Matrixd< States, Inputs > &B)
Definition: StateSpaceUtil.h:57
Definition: AprilTagPoseEstimator.h:15
WPILIB_DLLEXPORT Vectord< 4 > PoseTo4dVector(const Pose2d &pose)
Converts a Pose2d into a vector of [x, y, std::cos(theta), std::sin(theta)].
WPILIB_DLLEXPORT bool IsStabilizable< 2, 1 >(const Matrixd< 2, 2 > &A, const Matrixd< 2, 1 > &B)
Eigen::Vector< double, Size > Vectord
Definition: EigenCore.h:12
WPILIB_DLLEXPORT bool IsStabilizable< 1, 1 >(const Matrixd< 1, 1 > &A, const Matrixd< 1, 1 > &B)
Vectord< Inputs > ClampInputMaxMagnitude(const Vectord< Inputs > &u, const Vectord< Inputs > &umin, const Vectord< Inputs > &umax)
Clamps input vector between system's minimum and maximum allowable input.
Definition: StateSpaceUtil.h:297
Matrixd< sizeof...(Ts), sizeof...(Ts)> MakeCovMatrix(Ts... stdDevs)
Creates a covariance matrix from the given vector for use with Kalman filters.
Definition: StateSpaceUtil.h:119
bool IsStabilizable(const Matrixd< States, States > &A, const Matrixd< States, Inputs > &B)
Returns true if (A, B) is a stabilizable pair.
Definition: StateSpaceUtil.h:241
WPILIB_DLLEXPORT Vectord< 3 > PoseToVector(const Pose2d &pose)
Converts a Pose2d into a vector of [x, y, theta].
bool IsDetectable(const Matrixd< States, States > &A, const Matrixd< Outputs, States > &C)
Returns true if (A, C) is a detectable pair.
Definition: StateSpaceUtil.h:259
WPILIB_DLLEXPORT Vectord< 3 > PoseTo3dVector(const Pose2d &pose)
Converts a Pose2d into a vector of [x, y, theta].
Matrixd< sizeof...(Ts), 1 > MakeWhiteNoiseVector(Ts... stdDevs)
Definition: StateSpaceUtil.h:175
Vectord< Inputs > DesaturateInputVector(const Vectord< Inputs > &u, double maxMagnitude)
Renormalize all inputs if any exceeds the maximum magnitude.
Definition: StateSpaceUtil.h:317
Matrixd< sizeof...(Ts), sizeof...(Ts)> MakeCostMatrix(Ts... tolerances)
Creates a cost matrix from the given vector for use with LQR.
Definition: StateSpaceUtil.h:100
compound_unit< energy::joules, inverse< mass::kilogram > > rd
Definition: radiation.h:61
constexpr common_t< T1, T2 > pow(const T1 base, const T2 exp_term) noexcept
Compile-time power function.
Definition: pow.hpp:76