37template <
int States,
int Inputs,
int Outputs>
59 units::volt_t maxVoltage, units::second_t dt)
61 plant, controller, observer,
63 return frc::DesaturateInputVector<Inputs>(u, maxVoltage.value());
87 observer, clampFunction) {}
105 controller, feedforward, observer, [=](const
InputVector& u) {
106 return frc::DesaturateInputVector<Inputs>(u, maxVoltage.value());
171 double U(
int i)
const {
return U()(i); }
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
A Kalman filter combines predictions from a model and measurements to give an estimate of the true sy...
Definition: KalmanFilter.h:37
Constructs a plant inversion model-based feedforward from a LinearSystem.
Definition: LinearPlantInversionFeedforward.h:32
Contains the controller coefficients and logic for a linear-quadratic regulator (LQR).
Definition: LinearQuadraticRegulator.h:28
A plant defined using state-space notation.
Definition: LinearSystem.h:31
Combines a controller, feedforward, and observer for controlling a mechanism with full state feedback...
Definition: LinearSystemLoop.h:38
void Correct(const OutputVector &y)
Correct the state estimate x-hat using the measurements in y.
Definition: LinearSystemLoop.h:242
static constexpr int kOutputs
Definition: LinearSystemLoop.h:284
double NextR(int i) const
Returns an element of the controller's next reference r.
Definition: LinearSystemLoop.h:157
InputVector U() const
Returns the controller's calculated control input u.
Definition: LinearSystemLoop.h:162
void SetXhat(const StateVector &xHat)
Set the initial state estimate x-hat.
Definition: LinearSystemLoop.h:178
LinearSystemLoop(LinearSystem< States, Inputs, Outputs > &plant, LinearQuadraticRegulator< States, Inputs > &controller, KalmanFilter< States, Inputs, Outputs > &observer, std::function< InputVector(const InputVector &)> clampFunction, units::second_t dt)
Constructs a state-space loop with the given plant, controller, and observer.
Definition: LinearSystemLoop.h:79
void Reset(const StateVector &initialState)
Zeroes reference r and controller output u.
Definition: LinearSystemLoop.h:225
LinearSystemLoop(LinearSystem< States, Inputs, Outputs > &plant, LinearQuadraticRegulator< States, Inputs > &controller, KalmanFilter< States, Inputs, Outputs > &observer, units::volt_t maxVoltage, units::second_t dt)
Constructs a state-space loop with the given plant, controller, and observer.
Definition: LinearSystemLoop.h:56
Vectord< States > StateVector
Definition: LinearSystemLoop.h:40
const LinearQuadraticRegulator< States, Inputs > & Controller() const
Return the controller used internally.
Definition: LinearSystemLoop.h:198
LinearSystemLoop(LinearSystemLoop &&)=default
StateVector m_nextR
Definition: LinearSystemLoop.h:279
Vectord< Inputs > InputVector
Definition: LinearSystemLoop.h:41
LinearSystemLoop(LinearQuadraticRegulator< States, Inputs > &controller, const LinearPlantInversionFeedforward< States, Inputs > &feedforward, KalmanFilter< States, Inputs, Outputs > &observer, std::function< InputVector(const InputVector &)> clampFunction)
Constructs a state-space loop with the given controller, feedforward, observer and clamp function.
Definition: LinearSystemLoop.h:119
void SetNextR(const StateVector &nextR)
Set the next reference r.
Definition: LinearSystemLoop.h:193
LinearQuadraticRegulator< States, Inputs > * m_controller
Definition: LinearSystemLoop.h:269
Vectord< Outputs > OutputVector
Definition: LinearSystemLoop.h:42
void Predict(units::second_t dt)
Sets new controller output, projects model forward, and runs observer prediction.
Definition: LinearSystemLoop.h:253
double Xhat(int i) const
Returns an element of the observer's state estimate x-hat.
Definition: LinearSystemLoop.h:145
static constexpr int kStates
Definition: LinearSystemLoop.h:282
LinearSystemLoop & operator=(LinearSystemLoop &&)=default
double U(int i) const
Returns an element of the controller's calculated control input u.
Definition: LinearSystemLoop.h:171
const StateVector & NextR() const
Returns the controller's next reference r.
Definition: LinearSystemLoop.h:150
std::function< InputVector(const InputVector &)> m_clampFunc
Clamping function.
Definition: LinearSystemLoop.h:276
const KalmanFilter< States, Inputs, Outputs > & Observer() const
Return the observer used internally.
Definition: LinearSystemLoop.h:214
LinearPlantInversionFeedforward< States, Inputs > m_feedforward
Definition: LinearSystemLoop.h:270
const StateVector & Xhat() const
Returns the observer's state estimate x-hat.
Definition: LinearSystemLoop.h:138
InputVector ClampInput(const InputVector &u) const
Clamps input vector between system's minimum and maximum allowable input.
Definition: LinearSystemLoop.h:266
const LinearPlantInversionFeedforward< States, Inputs > Feedforward() const
Return the feedforward used internally.
Definition: LinearSystemLoop.h:207
static constexpr int kInputs
Definition: LinearSystemLoop.h:283
void SetXhat(int i, double value)
Set an element of the initial state estimate x-hat.
Definition: LinearSystemLoop.h:186
KalmanFilter< States, Inputs, Outputs > * m_observer
Definition: LinearSystemLoop.h:271
StateVector Error() const
Returns difference between reference r and current state x-hat.
Definition: LinearSystemLoop.h:235
LinearSystemLoop(LinearQuadraticRegulator< States, Inputs > &controller, const LinearPlantInversionFeedforward< States, Inputs > &feedforward, KalmanFilter< States, Inputs, Outputs > &observer, units::volt_t maxVoltage)
Constructs a state-space loop with the given controller, feedforward and observer.
Definition: LinearSystemLoop.h:100
const Scalar & y
Definition: MathFunctions.h:821
Definition: AprilTagFieldLayout.h:22
template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) LinearQuadraticRegulator< 1
Eigen::Vector< double, Size > Vectord
Definition: EigenCore.h:12