24template <
typename Matrix,
typename T,
typename... Ts>
26 if (elem == std::numeric_limits<double>::infinity()) {
31 if constexpr (
sizeof...(Ts) > 0) {
36template <
typename Matrix,
typename T,
typename... Ts>
39 if constexpr (
sizeof...(Ts) > 0) {
44template <
typename Matrix,
typename T,
typename... Ts>
46 std::random_device
rd;
47 std::mt19937 gen{
rd()};
48 std::normal_distribution<> distr{0.0, elem};
50 result(
result.rows() - (
sizeof...(Ts) + 1)) = distr(gen);
51 if constexpr (
sizeof...(Ts) > 0) {
56template <
int States,
int Inputs>
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() <
77 if (qr.rank() < States) {
99template <std::same_as<
double>... Ts>
118template <std::same_as<
double>... Ts>
141 auto& diag =
result.diagonal();
142 for (
size_t i = 0; i < N; ++i) {
143 if (costs[i] == std::numeric_limits<double>::infinity()) {
146 diag(i) = 1.0 /
std::pow(costs[i], 2);
167 auto& diag =
result.diagonal();
168 for (
size_t i = 0; i < N; ++i) {
174template <std::same_as<
double>... Ts>
191 std::random_device
rd;
192 std::mt19937 gen{
rd()};
195 for (
int i = 0; i < N; ++i) {
198 if (stdDevs[i] == 0.0) {
201 std::normal_distribution distr{0.0, stdDevs[i]};
240template <
int States,
int Inputs>
243 return detail::IsStabilizableImpl<States, Inputs>(A, B);
258template <
int States,
int Outputs>
261 return detail::IsStabilizableImpl<States, Outputs>(A.transpose(),
301 for (
int i = 0; i < Inputs; ++i) {
302 result(i) = std::clamp(u(i), umin(i), umax(i));
318 double maxMagnitude) {
319 double maxValue = u.template lpNorm<Eigen::Infinity>();
321 if (maxValue > maxMagnitude) {
322 return u * maxMagnitude / maxValue;
#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