WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
wpi::math::detail Namespace Reference

Functions

WPILIB_DLLEXPORT int IncrementAndGetProfiledPIDControllerInstances ()
template<int States, int Inputs>
Eigen::Matrix< double, States, States > DARE (const Eigen::Matrix< double, States, States > &A, const Eigen::Matrix< double, States, Inputs > &B, const Eigen::Matrix< double, States, States > &Q, const Eigen::LLT< Eigen::Matrix< double, Inputs, Inputs > > &R_llt)
 Computes the unique stabilizing solution X to the discrete-time algebraic Riccati equation:
constexpr ct_matrix3d RotationVectorToMatrix (const ct_vector3d &rotation)
constexpr Eigen::Matrix3d RotationVectorToMatrix (const Eigen::Vector3d &rotation)

Function Documentation

◆ DARE()

template<int States, int Inputs>
Eigen::Matrix< double, States, States > wpi::math::detail::DARE ( const Eigen::Matrix< double, States, States > & A,
const Eigen::Matrix< double, States, Inputs > & B,
const Eigen::Matrix< double, States, States > & Q,
const Eigen::LLT< Eigen::Matrix< double, Inputs, Inputs > > & R_llt )

Computes the unique stabilizing solution X to the discrete-time algebraic Riccati equation:

AᵀXA − X − AᵀXB(BᵀXB + R)⁻¹BᵀXA + Q = 0

This internal function skips expensive precondition checks for increased performance. The solver may hang if any of the following occur:

  • Q isn't symmetric positive semidefinite
  • R isn't symmetric positive definite
  • The (A, B) pair isn't stabilizable
  • The (A, C) pair where Q = CᵀC isn't detectable

Only use this function if you're sure the preconditions are met.

Template Parameters
StatesNumber of states.
InputsNumber of inputs.
Parameters
AThe system matrix.
BThe input matrix.
QThe state cost matrix.
R_lltThe LLT decomposition of the input cost matrix.
Returns
Solution to the DARE.

◆ IncrementAndGetProfiledPIDControllerInstances()

WPILIB_DLLEXPORT int wpi::math::detail::IncrementAndGetProfiledPIDControllerInstances ( )

◆ RotationVectorToMatrix() [1/2]

ct_matrix3d wpi::math::detail::RotationVectorToMatrix ( const ct_vector3d & rotation)
constexpr

◆ RotationVectorToMatrix() [2/2]

Eigen::Matrix3d wpi::math::detail::RotationVectorToMatrix ( const Eigen::Vector3d & rotation)
constexpr