13#include <Eigen/Eigenvalues>
36template <std::same_as<
double>... Ts>
38 Eigen::DiagonalMatrix<double,
sizeof...(Ts)> result;
39 auto& diag = result.diagonal();
41 [&](
int i,
double tolerance) {
42 if (tolerance == std::numeric_limits<double>::infinity()) {
45 diag(i) = 1.0 /
std::pow(tolerance, 2);
64template <std::same_as<
double>... Ts>
66 Eigen::DiagonalMatrix<double,
sizeof...(Ts)> result;
67 auto& diag = result.diagonal();
88 Eigen::DiagonalMatrix<double, N> result;
89 auto& diag = result.diagonal();
90 for (
size_t i = 0; i < costs.size(); ++i) {
91 if (costs[i] == std::numeric_limits<double>::infinity()) {
94 diag(i) = 1.0 /
std::pow(costs[i], 2);
114 Eigen::DiagonalMatrix<double, N> result;
115 auto& diag = result.diagonal();
116 for (
size_t i = 0; i < N; ++i) {
122template <std::same_as<
double>... Ts>
124 std::random_device
rd;
125 std::mt19937 gen{
rd()};
129 [&](
int i,
double stdDev) {
135 std::normal_distribution distr{0.0, stdDev};
136 result(i) = distr(gen);
153 std::random_device
rd;
154 std::mt19937 gen{
rd()};
157 for (
size_t i = 0; i < stdDevs.size(); ++i) {
160 if (stdDevs[i] == 0.0) {
163 std::normal_distribution distr{0.0, stdDevs[i]};
164 result(i) = distr(gen);
202template <
int States,
int Inputs>
205 Eigen::EigenSolver<Matrixd<States, States>> es{A,
false};
207 for (
int i = 0; i < A.rows(); ++i) {
208 if (std::norm(es.eigenvalues()[i]) < 1) {
212 if constexpr (States != Eigen::Dynamic && Inputs != Eigen::Dynamic) {
213 Eigen::Matrix<std::complex<double>, States, States + Inputs> E;
214 E << es.eigenvalues()[i] * Eigen::Matrix<std::complex<double>, States,
215 States>::Identity() -
219 Eigen::ColPivHouseholderQR<
220 Eigen::Matrix<std::complex<double>, States, States + Inputs>>
222 if (qr.rank() < States) {
226 Eigen::MatrixXcd E{A.rows(), A.rows() + B.cols()};
227 E << es.eigenvalues()[i] *
228 Eigen::MatrixXcd::Identity(A.rows(), A.rows()) -
232 Eigen::ColPivHouseholderQR<Eigen::MatrixXcd> qr{E};
233 if (qr.rank() < A.rows()) {
246IsStabilizable<Eigen::Dynamic, Eigen::Dynamic>(
const Eigen::MatrixXd& A,
247 const Eigen::MatrixXd& B);
261template <
int States,
int Outputs>
264 return IsStabilizable<States, Outputs>(A.transpose(), C.transpose());
291 for (
int i = 0; i < Inputs; ++i) {
292 result(i) = std::clamp(u(i), umin(i), umax(i));
308 double maxMagnitude) {
309 double maxValue = u.template lpNorm<Eigen::Infinity>();
311 if (maxValue > maxMagnitude) {
312 return u * maxMagnitude / maxValue;
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
Definition: AprilTagPoseEstimator.h:15
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:287
Matrixd< sizeof...(Ts), sizeof...(Ts)> MakeCovMatrix(Ts... stdDevs)
Creates a covariance matrix from the given vector for use with Kalman filters.
Definition: StateSpaceUtil.h:65
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:203
Vectord< sizeof...(Ts)> MakeWhiteNoiseVector(Ts... stdDevs)
Definition: StateSpaceUtil.h:123
bool IsDetectable(const Matrixd< States, States > &A, const Matrixd< Outputs, States > &C)
Returns true if (A, C) is a detectable pair.
Definition: StateSpaceUtil.h:262
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:307
Matrixd< sizeof...(Ts), sizeof...(Ts)> MakeCostMatrix(Ts... tolerances)
Creates a cost matrix from the given vector for use with LQR.
Definition: StateSpaceUtil.h:37
WPILIB_DLLEXPORT Eigen::Vector4d PoseTo4dVector(const Pose2d &pose)
Converts a Pose2d into a vector of [x, y, std::cos(theta), std::sin(theta)].
auto pow(const UnitType &value) noexcept -> unit_t< typename units::detail::power_of_unit< power, typename units::traits::unit_t_traits< UnitType >::unit_type >::type, typename units::traits::unit_t_traits< UnitType >::underlying_type, linear_scale >
computes the value of value raised to the power
Definition: base.h:2806
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