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