24template <
int Rows,
int Cols,
typename Matrix,
typename T,
typename... Ts>
26 constexpr int count = Rows * Cols - (
sizeof...(Ts) + 1);
29 if constexpr (
sizeof...(Ts) > 0) {
30 MatrixImpl<Rows, Cols>(
result, elems...);
34template <
typename Matrix,
typename T,
typename... Ts>
36 if (elem == std::numeric_limits<double>::infinity()) {
41 if constexpr (
sizeof...(Ts) > 0) {
46template <
typename Matrix,
typename T,
typename... Ts>
49 if constexpr (
sizeof...(Ts) > 0) {
54template <
typename Matrix,
typename T,
typename... Ts>
56 std::random_device
rd;
57 std::mt19937 gen{
rd()};
58 std::normal_distribution<> distr{0.0, elem};
60 result(
result.rows() - (
sizeof...(Ts) + 1)) = distr(gen);
61 if constexpr (
sizeof...(Ts) > 0) {
66template <
int States,
int Inputs>
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() <
87 if (qr.rank() < States) {
110 std::conjunction_v<std::is_same<double, Ts>...>>>
130 std::conjunction_v<std::is_same<double, Ts>...>>>
153 auto& diag =
result.diagonal();
154 for (
size_t i = 0; i < N; ++i) {
155 if (costs[i] == std::numeric_limits<double>::infinity()) {
158 diag(i) = 1.0 /
std::pow(costs[i], 2);
179 auto& diag =
result.diagonal();
180 for (
size_t i = 0; i < N; ++i) {
187 std::conjunction_v<std::is_same<double, Ts>...>>>
204 std::random_device
rd;
205 std::mt19937 gen{
rd()};
208 for (
int i = 0; i < N; ++i) {
211 if (stdDevs[i] == 0.0) {
214 std::normal_distribution distr{0.0, stdDevs[i]};
253template <
int States,
int Inputs>
256 return detail::IsStabilizableImpl<States, Inputs>(A, B);
271template <
int States,
int Outputs>
274 return detail::IsStabilizableImpl<States, Outputs>(A.transpose(),
314 for (
int i = 0; i < Inputs; ++i) {
315 result(i) = std::clamp(u(i), umin(i), umax(i));
331 double maxMagnitude) {
332 double maxValue = u.template lpNorm<Eigen::Infinity>();
334 if (maxValue > maxMagnitude) {
335 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
typename std::enable_if< B, T >::type enable_if_t
Definition: core.h:298
constexpr auto count() -> size_t
Definition: core.h:1204
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