10 #ifdef USE_MATLAB_CPP_INTERFACE 11 #include <matlabCppInterface/Engine.hpp> 31 template <
size_t STATE_DIM,
size_t CONTROL_DIM>
35 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
55 bool compute(
const state_matrix_t& Q,
56 const control_matrix_t& R,
57 const state_matrix_t& A,
58 const control_gain_matrix_t& B,
59 control_feedback_t& K,
60 bool RisDiagonal =
false,
61 bool solveRiccatiIteratively =
false);
63 #ifdef USE_MATLAB_CPP_INTERFACE 68 bool computeMatlab(
const state_matrix_t& Q,
69 const control_matrix_t& R,
70 const state_matrix_t& A,
71 const control_gain_matrix_t& B,
72 control_feedback_t& K,
73 bool checkControllability =
false);
74 #endif //USE_MATLAB_CPP_INTERFACE 80 #ifdef USE_MATLAB_CPP_INTERFACE 81 matlab::Engine matlabEngine_;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef Eigen::Matrix< double, STATE_DIM, STATE_DIM > state_matrix_t
Definition: LQR.hpp:37
Eigen::Matrix< double, STATE_DIM, CONTROL_DIM > control_gain_matrix_t
Definition: LQR.hpp:40
continuous-time infinite-horizon LQR
Definition: LQR.hpp:32
Continuous-Time Algebraic Riccati Equation.
Definition: CARE.hpp:46
Eigen::Matrix< double, CONTROL_DIM, STATE_DIM > control_state_matrix_t
Definition: LQR.hpp:39
Eigen::Matrix< double, CONTROL_DIM, CONTROL_DIM > control_matrix_t
Definition: LQR.hpp:38
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.
Definition: LQR-impl.hpp:16
Eigen::Matrix< double, CONTROL_DIM, STATE_DIM > control_feedback_t
Definition: LQR.hpp:41