- 3.0.2 optimal control module.
ct::optcon::LQR< STATE_DIM, CONTROL_DIM > Class Template Reference

continuous-time infinite-horizon LQR More...

#include <LQR.hpp>

Public Types

typedef Eigen::Matrix< double, CONTROL_DIM, CONTROL_DIM > control_matrix_t
 
typedef Eigen::Matrix< double, CONTROL_DIM, STATE_DIM > control_state_matrix_t
 
typedef Eigen::Matrix< double, STATE_DIM, CONTROL_DIM > control_gain_matrix_t
 
typedef Eigen::Matrix< double, CONTROL_DIM, STATE_DIM > control_feedback_t
 

Public Member Functions

bool compute (const state_matrix_t &Q, const control_matrix_t &R, const state_matrix_t &A, const control_gain_matrix_t &B, control_feedback_t &K, bool RisDiagonal=false, bool solveRiccatiIteratively=false)
 design the infinite-horizon LQR controller. More...
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef Eigen::Matrix< double, STATE_DIM, STATE_DIM > state_matrix_t
 

Detailed Description

template<size_t STATE_DIM, size_t CONTROL_DIM>
class ct::optcon::LQR< STATE_DIM, CONTROL_DIM >

continuous-time infinite-horizon LQR

Implements continous-time infinite-horizon LQR. Resulting feedback law will take the form

\[ u_{fb} = -K \cdot (x - x_{ref}) \]

Template Parameters
STATE_DIM
CONTROL_DIM
Examples:
LQR.cpp, and LqrTest.h.

Member Typedef Documentation

◆ control_matrix_t

template<size_t STATE_DIM, size_t CONTROL_DIM>
typedef Eigen::Matrix<double, CONTROL_DIM, CONTROL_DIM> ct::optcon::LQR< STATE_DIM, CONTROL_DIM >::control_matrix_t

◆ control_state_matrix_t

template<size_t STATE_DIM, size_t CONTROL_DIM>
typedef Eigen::Matrix<double, CONTROL_DIM, STATE_DIM> ct::optcon::LQR< STATE_DIM, CONTROL_DIM >::control_state_matrix_t

◆ control_gain_matrix_t

template<size_t STATE_DIM, size_t CONTROL_DIM>
typedef Eigen::Matrix<double, STATE_DIM, CONTROL_DIM> ct::optcon::LQR< STATE_DIM, CONTROL_DIM >::control_gain_matrix_t

◆ control_feedback_t

template<size_t STATE_DIM, size_t CONTROL_DIM>
typedef Eigen::Matrix<double, CONTROL_DIM, STATE_DIM> ct::optcon::LQR< STATE_DIM, CONTROL_DIM >::control_feedback_t

Member Function Documentation

◆ compute()

template<size_t STATE_DIM, size_t CONTROL_DIM>
bool ct::optcon::LQR< STATE_DIM, CONTROL_DIM >::compute ( const state_matrix_t Q,
const control_matrix_t R,
const state_matrix_t A,
const control_gain_matrix_t B,
control_feedback_t K,
bool  RisDiagonal = false,
bool  solveRiccatiIteratively = false 
)

design the infinite-horizon LQR controller.

Parameters
Qstate-weighting matrix
Rcontrol input weighting matrix
Alinear system dynamics matrix A
Blinear system dynamics matrix B
Kcontrol feedback matrix K (to be designed)
RisDiagonalset to true if R is a diagonal matrix (efficiency boost)
solveRiccatiIterativelyuse closed-form solution of the infinite-horizon Riccati Equation
Returns
success

Referenced by main(), and ct::optcon::example::TEST().

Member Data Documentation

◆ state_matrix_t

template<size_t STATE_DIM, size_t CONTROL_DIM>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef Eigen::Matrix<double, STATE_DIM, STATE_DIM> ct::optcon::LQR< STATE_DIM, CONTROL_DIM >::state_matrix_t

The documentation for this class was generated from the following files: