WPILibC++ 2027.0.0-alpha-2
Loading...
Searching...
No Matches
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(row, col) = 0.0;
45 }
46 }
47 }
48
50 [&](int i, double tolerance) {
51 if (tolerance == std::numeric_limits<double>::infinity()) {
52 result(i, i) = 0.0;
53 } else {
54 result(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(row, col) = 0.0;
82 }
83 }
84 }
85
86 wpi::for_each([&](int i, double stdDev) { result(i, i) = stdDev * stdDev; },
87 stdDevs...);
88
89 return result;
90}
91
92/**
93 * Creates a cost matrix from the given vector for use with LQR.
94 *
95 * The cost matrix is constructed using Bryson's rule. The inverse square of
96 * each element in the input is placed on the cost matrix diagonal. If a
97 * tolerance is infinity, its cost matrix entry is set to zero.
98 *
99 * @param costs An array. For a Q matrix, its elements are the maximum allowed
100 * excursions of the states from the reference. For an R matrix,
101 * its elements are the maximum allowed excursions of the control
102 * inputs from no actuation.
103 * @return State excursion or control effort cost matrix.
104 */
105template <size_t N>
106constexpr Matrixd<N, N> MakeCostMatrix(const std::array<double, N>& costs) {
107 Matrixd<N, N> result;
108
109 for (int row = 0; row < result.rows(); ++row) {
110 for (int col = 0; col < result.cols(); ++col) {
111 if (row == col) {
112 if (costs[row] == std::numeric_limits<double>::infinity()) {
113 result(row, col) = 0.0;
114 } else {
115 result(row, col) = 1.0 / (costs[row] * costs[row]);
116 }
117 } else {
118 result(row, col) = 0.0;
119 }
120 }
121 }
122
123 return result;
124}
125
126/**
127 * Creates a cost matrix from the given vector for use with LQR.
128 *
129 * The cost matrix is constructed using Bryson's rule. The inverse square of
130 * each element in the input is placed on the cost matrix diagonal. If a
131 * tolerance is infinity, its cost matrix entry is set to zero.
132 *
133 * @param costs A possibly variable length container. For a Q matrix, its
134 * elements are the maximum allowed excursions of the states from
135 * the reference. For an R matrix, its elements are the maximum
136 * allowed excursions of the control inputs from no actuation.
137 * @return State excursion or control effort cost matrix.
138 */
140 const std::span<const double> costs);
141
142/**
143 * Creates a covariance matrix from the given vector for use with Kalman
144 * filters.
145 *
146 * Each element is squared and placed on the covariance matrix diagonal.
147 *
148 * @param stdDevs An array. For a Q matrix, its elements are the standard
149 * deviations of each state from how the model behaves. For an R
150 * matrix, its elements are the standard deviations for each
151 * output measurement.
152 * @return Process noise or measurement noise covariance matrix.
153 */
154template <size_t N>
155constexpr Matrixd<N, N> MakeCovMatrix(const std::array<double, N>& stdDevs) {
156 Matrixd<N, N> result;
157
158 for (int row = 0; row < result.rows(); ++row) {
159 for (int col = 0; col < result.cols(); ++col) {
160 if (row == col) {
161 result(row, col) = stdDevs[row] * stdDevs[row];
162 } else {
163 result(row, col) = 0.0;
164 }
165 }
166 }
167
168 return result;
169}
170
171/**
172 * Creates a covariance matrix from the given vector for use with Kalman
173 * filters.
174 *
175 * Each element is squared and placed on the covariance matrix diagonal.
176 *
177 * @param stdDevs A possibly variable length container. For a Q matrix, its
178 * elements are the standard deviations of each state from how
179 * the model behaves. For an R matrix, its elements are the
180 * standard deviations for each output measurement.
181 * @return Process noise or measurement noise covariance matrix.
182 */
184 const std::span<const double> stdDevs);
185
186template <std::same_as<double>... Ts>
187Vectord<sizeof...(Ts)> MakeWhiteNoiseVector(Ts... stdDevs) {
188 std::random_device rd;
189 std::mt19937 gen{rd()};
190
191 Vectord<sizeof...(Ts)> result;
193 [&](int i, double stdDev) {
194 // Passing a standard deviation of 0.0 to std::normal_distribution is
195 // undefined behavior
196 if (stdDev == 0.0) {
197 result(i) = 0.0;
198 } else {
199 std::normal_distribution distr{0.0, stdDev};
200 result(i) = distr(gen);
201 }
202 },
203 stdDevs...);
204 return result;
205}
206
207/**
208 * Creates a vector of normally distributed white noise with the given noise
209 * intensities for each element.
210 *
211 * @param stdDevs An array whose elements are the standard deviations of each
212 * element of the noise vector.
213 * @return White noise vector.
214 */
215template <int N>
216Vectord<N> MakeWhiteNoiseVector(const std::array<double, N>& stdDevs) {
217 std::random_device rd;
218 std::mt19937 gen{rd()};
219
220 Vectord<N> result;
221 for (size_t i = 0; i < stdDevs.size(); ++i) {
222 // Passing a standard deviation of 0.0 to std::normal_distribution is
223 // undefined behavior
224 if (stdDevs[i] == 0.0) {
225 result(i) = 0.0;
226 } else {
227 std::normal_distribution distr{0.0, stdDevs[i]};
228 result(i) = distr(gen);
229 }
230 }
231 return result;
232}
233
234/**
235 * Creates a vector of normally distributed white noise with the given noise
236 * intensities for each element.
237 *
238 * @param stdDevs A possibly variable length container whose elements are the
239 * standard deviations of each element of the noise vector.
240 * @return White noise vector.
241 */
243 const std::span<const double> stdDevs);
244
245/**
246 * Converts a Pose2d into a vector of [x, y, theta].
247 *
248 * @param pose The pose that is being represented.
249 *
250 * @return The vector.
251 * @deprecated Create the vector manually instead. If you were using this as an
252 * intermediate step for constructing affine transformations, use
253 * Pose2d.ToMatrix() instead.
254 */
255[[deprecated("Use Pose2d.ToMatrix() instead.")]]
256WPILIB_DLLEXPORT constexpr Eigen::Vector3d PoseTo3dVector(const Pose2d& pose) {
257 return Eigen::Vector3d{{pose.Translation().X().value(),
258 pose.Translation().Y().value(),
259 pose.Rotation().Radians().value()}};
260}
261
262/**
263 * Converts a Pose2d into a vector of [x, y, std::cos(theta), std::sin(theta)].
264 *
265 * @param pose The pose that is being represented.
266 *
267 * @return The vector.
268 * @deprecated Create the vector manually instead. If you were using this as an
269 * intermediate step for constructing affine transformations, use
270 * Pose2d.ToMatrix() instead.
271 */
272[[deprecated("Use Pose2d.ToMatrix() instead.")]]
273WPILIB_DLLEXPORT constexpr Eigen::Vector4d PoseTo4dVector(const Pose2d& pose) {
274 return Eigen::Vector4d{{pose.Translation().X().value(),
275 pose.Translation().Y().value(), pose.Rotation().Cos(),
276 pose.Rotation().Sin()}};
277}
278
279/**
280 * Returns true if (A, B) is a stabilizable pair.
281 *
282 * (A, B) is stabilizable if and only if the uncontrollable eigenvalues of A, if
283 * any, have absolute values less than one, where an eigenvalue is
284 * uncontrollable if rank([λI - A, B]) < n where n is the number of states.
285 *
286 * @tparam States Number of states.
287 * @tparam Inputs Number of inputs.
288 * @param A System matrix.
289 * @param B Input matrix.
290 */
291template <int States, int Inputs>
293 const Matrixd<States, Inputs>& B) {
294 Eigen::EigenSolver<Matrixd<States, States>> es{A, false};
295
296 for (int i = 0; i < A.rows(); ++i) {
297 if (std::norm(es.eigenvalues()[i]) < 1) {
298 continue;
299 }
300
301 if constexpr (States != Eigen::Dynamic && Inputs != Eigen::Dynamic) {
302 Eigen::Matrix<std::complex<double>, States, States + Inputs> E;
303 E << es.eigenvalues()[i] * Eigen::Matrix<std::complex<double>, States,
304 States>::Identity() -
305 A,
306 B;
307
308 Eigen::ColPivHouseholderQR<
309 Eigen::Matrix<std::complex<double>, States, States + Inputs>>
310 qr{E};
311 if (qr.rank() < States) {
312 return false;
313 }
314 } else {
315 Eigen::MatrixXcd E{A.rows(), A.rows() + B.cols()};
316 E << es.eigenvalues()[i] *
317 Eigen::MatrixXcd::Identity(A.rows(), A.rows()) -
318 A,
319 B;
320
321 Eigen::ColPivHouseholderQR<Eigen::MatrixXcd> qr{E};
322 if (qr.rank() < A.rows()) {
323 return false;
324 }
325 }
326 }
327 return true;
328}
329
331 const Matrixd<1, 1>& A, const Matrixd<1, 1>& B);
333 const Matrixd<2, 2>& A, const Matrixd<2, 1>& B);
334extern template WPILIB_DLLEXPORT bool
336 const Eigen::MatrixXd& B);
337
338/**
339 * Returns true if (A, C) is a detectable pair.
340 *
341 * (A, C) is detectable if and only if the unobservable eigenvalues of A, if
342 * any, have absolute values less than one, where an eigenvalue is unobservable
343 * if rank([λI - A; C]) < n where n is the number of states.
344 *
345 * @tparam States Number of states.
346 * @tparam Outputs Number of outputs.
347 * @param A System matrix.
348 * @param C Output matrix.
349 */
350template <int States, int Outputs>
352 const Matrixd<Outputs, States>& C) {
353 return IsStabilizable<States, Outputs>(A.transpose(), C.transpose());
354}
355
356extern template WPILIB_DLLEXPORT bool
357IsDetectable<Eigen::Dynamic, Eigen::Dynamic>(const Eigen::MatrixXd& A,
358 const Eigen::MatrixXd& C);
359
360/**
361 * Converts a Pose2d into a vector of [x, y, theta].
362 *
363 * @param pose The pose that is being represented.
364 *
365 * @return The vector.
366 * @deprecated Create the vector manually instead. If you were using this as an
367 * intermediate step for constructing affine transformations, use
368 * Pose2d.ToMatrix() instead.
369 */
370[[deprecated("Use Pose2d.ToMatrix() instead.")]]
371WPILIB_DLLEXPORT constexpr Eigen::Vector3d PoseToVector(const Pose2d& pose) {
372 return Eigen::Vector3d{
373 {pose.X().value(), pose.Y().value(), pose.Rotation().Radians().value()}};
374}
375
376/**
377 * Clamps input vector between system's minimum and maximum allowable input.
378 *
379 * @tparam Inputs Number of inputs.
380 * @param u Input vector to clamp.
381 * @param umin The minimum input magnitude.
382 * @param umax The maximum input magnitude.
383 * @return Clamped input vector.
384 */
385template <int Inputs>
387 const Vectord<Inputs>& umin,
388 const Vectord<Inputs>& umax) {
389 Vectord<Inputs> result;
390 for (int i = 0; i < u.rows(); ++i) {
391 result(i) = std::clamp(u(i), umin(i), umax(i));
392 }
393 return result;
394}
395
396extern template WPILIB_DLLEXPORT Eigen::VectorXd
397ClampInputMaxMagnitude<Eigen::Dynamic>(const Eigen::VectorXd& u,
398 const Eigen::VectorXd& umin,
399 const Eigen::VectorXd& umax);
400
401/**
402 * Renormalize all inputs if any exceeds the maximum magnitude. Useful for
403 * systems such as differential drivetrains.
404 *
405 * @tparam Inputs Number of inputs.
406 * @param u The input vector.
407 * @param maxMagnitude The maximum magnitude any input can have.
408 * @return The normalizedInput
409 */
410template <int Inputs>
412 double maxMagnitude) {
413 double maxValue = u.template lpNorm<Eigen::Infinity>();
414
415 if (maxValue > maxMagnitude) {
416 return u * maxMagnitude / maxValue;
417 }
418 return u;
419}
420
421extern template WPILIB_DLLEXPORT Eigen::VectorXd
422DesaturateInputVector<Eigen::Dynamic>(const Eigen::VectorXd& u,
423 double maxMagnitude);
424
425} // namespace frc
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.h:28
constexpr const Rotation2d & Rotation() const
Returns the underlying rotation.
Definition Pose2d.h:128
constexpr units::meter_t Y() const
Returns the Y component of the pose's translation.
Definition Pose2d.h:121
constexpr units::meter_t X() const
Returns the X component of the pose's translation.
Definition Pose2d.h:114
constexpr const Translation2d & Translation() const
Returns the underlying translation.
Definition Pose2d.h:107
constexpr double Cos() const
Returns the cosine of the rotation.
Definition Rotation2d.h:222
constexpr double Sin() const
Returns the sine of the rotation.
Definition Rotation2d.h:229
constexpr units::radian_t Radians() const
Returns the radian value of the rotation constrained within [-π, π].
Definition Rotation2d.h:206
constexpr units::meter_t X() const
Returns the X component of the translation.
Definition Translation2d.h:83
constexpr units::meter_t Y() const
Returns the Y component of the translation.
Definition Translation2d.h:90
Definition SystemServer.h:9
WPILIB_DLLEXPORT constexpr Eigen::Vector3d PoseTo3dVector(const Pose2d &pose)
Converts a Pose2d into a vector of [x, y, theta].
Definition StateSpaceUtil.h:256
Eigen::Matrix< double, Rows, Cols, Options, MaxRows, MaxCols > Matrixd
Definition EigenCore.h:21
template 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
template WPILIB_DLLEXPORT bool IsStabilizable< Eigen::Dynamic, Eigen::Dynamic >(const Eigen::MatrixXd &A, const Eigen::MatrixXd &B)
bool IsStabilizable(const Matrixd< States, States > &A, const Matrixd< States, Inputs > &B)
Returns true if (A, B) is a stabilizable pair.
Definition StateSpaceUtil.h:292
constexpr 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:386
Vectord< sizeof...(Ts)> MakeWhiteNoiseVector(Ts... stdDevs)
Definition StateSpaceUtil.h:187
template WPILIB_DLLEXPORT bool IsDetectable< Eigen::Dynamic, Eigen::Dynamic >(const Eigen::MatrixXd &A, const Eigen::MatrixXd &C)
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:351
template WPILIB_DLLEXPORT bool IsStabilizable< 1, 1 >(const Matrixd< 1, 1 > &A, const Matrixd< 1, 1 > &B)
WPILIB_DLLEXPORT constexpr Eigen::Vector3d PoseToVector(const Pose2d &pose)
Converts a Pose2d into a vector of [x, y, theta].
Definition StateSpaceUtil.h:371
template WPILIB_DLLEXPORT Eigen::VectorXd ClampInputMaxMagnitude< Eigen::Dynamic >(const Eigen::VectorXd &u, const Eigen::VectorXd &umin, const Eigen::VectorXd &umax)
WPILIB_DLLEXPORT constexpr Eigen::Vector4d PoseTo4dVector(const Pose2d &pose)
Converts a Pose2d into a vector of [x, y, std::cos(theta), std::sin(theta)].
Definition StateSpaceUtil.h:273
template WPILIB_DLLEXPORT Eigen::VectorXd DesaturateInputVector< Eigen::Dynamic >(const Eigen::VectorXd &u, double maxMagnitude)
Vectord< Inputs > DesaturateInputVector(const Vectord< Inputs > &u, double maxMagnitude)
Renormalize all inputs if any exceeds the maximum magnitude.
Definition StateSpaceUtil.h:411
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
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