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