- 3.0.2 optimal control module.
LQR.hpp
Go to the documentation of this file.
1 /**********************************************************************************************************************
2 This file is part of the Control Toolbox (https://github.com/ethz-adrl/control-toolbox), copyright by ETH Zurich.
3 Licensed under the BSD-2 license (see LICENSE file in main directory)
4 **********************************************************************************************************************/
5 
6 #pragma once
7 
8 #include "riccati/CARE.hpp"
9 
10 #ifdef USE_MATLAB_CPP_INTERFACE
11 #include <matlabCppInterface/Engine.hpp>
12 #endif
13 
14 namespace ct {
15 namespace optcon {
16 
31 template <size_t STATE_DIM, size_t CONTROL_DIM>
32 class LQR
33 {
34 public:
35  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
36 
37  typedef Eigen::Matrix<double, STATE_DIM, STATE_DIM> state_matrix_t;
38  typedef Eigen::Matrix<double, CONTROL_DIM, CONTROL_DIM> control_matrix_t;
39  typedef Eigen::Matrix<double, CONTROL_DIM, STATE_DIM> control_state_matrix_t;
40  typedef Eigen::Matrix<double, STATE_DIM, CONTROL_DIM> control_gain_matrix_t;
41  typedef Eigen::Matrix<double, CONTROL_DIM, STATE_DIM> control_feedback_t;
42 
44 
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);
62 
63 #ifdef USE_MATLAB_CPP_INTERFACE
64 
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
75 
76 
77 private:
78  CARE<STATE_DIM, CONTROL_DIM> care_; // continuous-time algebraic riccati equation
79 
80 #ifdef USE_MATLAB_CPP_INTERFACE
81  matlab::Engine matlabEngine_;
82 #endif
83 };
84 
85 
86 } // namespace optcon
87 } // namespace ct
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