10 #ifdef MATLAB_FULL_LOG 21 template <
size_t STATE_DIM,
size_t CONTROL_DIM,
typename SCALAR =
double>
25 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
43 GNRiccatiSolver(
const std::shared_ptr<LQOCProblem_t>& lqocProblem =
nullptr);
47 virtual void solve()
override;
68 virtual void setProblemImpl(std::shared_ptr<LQOCProblem_t> lqocProblem)
override;
82 ControlVectorArray
gv_;
85 ControlMatrixArray
H_;
86 ControlMatrixArray
Hi_;
98 Eigen::SelfAdjointEigenSolver<Eigen::Matrix<SCALAR, CONTROL_DIM, CONTROL_DIM>>
eigenvalueSolver_;
101 #ifdef MATLAB_FULL_LOG ct::core::ControlVectorArray< CONTROL_DIM, SCALAR > ControlVectorArray
Definition: GNRiccatiSolver.hpp:41
void changeNumberOfStages(int N)
Definition: GNRiccatiSolver-impl.hpp:103
ct::core::StateMatrix< STATE_DIM, SCALAR > StateMatrix
Definition: GNRiccatiSolver.hpp:32
virtual void compute_lv() override
compute iLQR-style lv
Definition: GNRiccatiSolver-impl.hpp:78
ControlMatrix H_corrFix_
Definition: GNRiccatiSolver.hpp:88
virtual void setProblemImpl(std::shared_ptr< LQOCProblem_t > lqocProblem) override
Definition: GNRiccatiSolver-impl.hpp:89
SCALAR smallestEigenvalue_
Definition: GNRiccatiSolver.hpp:95
LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR > LQOCProblem_t
Definition: GNRiccatiSolver.hpp:30
static const int control_dim
Definition: GNRiccatiSolver.hpp:28
static EIGEN_MAKE_ALIGNED_OPERATOR_NEW const int state_dim
Definition: GNRiccatiSolver.hpp:27
virtual void solve() override
solve the LQOC problem
Definition: GNRiccatiSolver-impl.hpp:28
virtual SCALAR getSmallestEigenvalue() override
return the smallest eigenvalue
Definition: GNRiccatiSolver-impl.hpp:83
ct::core::StateVectorArray< STATE_DIM, SCALAR > StateVectorArray
Definition: GNRiccatiSolver.hpp:40
virtual void configure(const NLOptConSettings &settings) override
Definition: GNRiccatiSolver-impl.hpp:49
ct::core::ControlVector< CONTROL_DIM, SCALAR > ControlVector
Definition: GNRiccatiSolver.hpp:34
ct::core::ControlMatrix< CONTROL_DIM, SCALAR > ControlMatrix
Definition: GNRiccatiSolver.hpp:35
Settings for the NLOptCon algorithm.
Definition: NLOptConSettings.hpp:198
CppAD::AD< CppAD::cg::CG< double > > SCALAR
void initializeCostToGo()
Definition: GNRiccatiSolver-impl.hpp:132
void designController(size_t k)
Definition: GNRiccatiSolver-impl.hpp:167
Defines a Linear-Quadratic Optimal Control Problem, which is optionally constrained.
Definition: LQOCProblem.hpp:57
void logToMatlab()
Definition: GNRiccatiSolver-impl.hpp:266
GNRiccatiSolver(const std::shared_ptr< LQOCProblem_t > &lqocProblem=nullptr)
Definition: GNRiccatiSolver-impl.hpp:13
ct::core::StateControlMatrixArray< STATE_DIM, CONTROL_DIM, SCALAR > StateControlMatrixArray
Definition: GNRiccatiSolver.hpp:37
ControlMatrixArray H_
Definition: GNRiccatiSolver.hpp:85
StateMatrixArray S_
Definition: GNRiccatiSolver.hpp:91
Definition: GNRiccatiSolver.hpp:22
ct::core::StateMatrixArray< STATE_DIM, SCALAR > StateMatrixArray
Definition: GNRiccatiSolver.hpp:33
ControlMatrixArray Hi_inverse_
Definition: GNRiccatiSolver.hpp:87
void computeCostToGo(size_t k)
Definition: GNRiccatiSolver-impl.hpp:147
virtual void computeStatesAndControls() override
extract the solution (can be overriden if additional extraction steps required in specific solver) ...
Definition: GNRiccatiSolver-impl.hpp:56
virtual void computeFeedbackMatrices() override
return TVLQR feedback matrices
Definition: GNRiccatiSolver-impl.hpp:73
ct::core::ControlMatrixArray< CONTROL_DIM, SCALAR > ControlMatrixArray
Definition: GNRiccatiSolver.hpp:36
ControlMatrixArray Hi_
Definition: GNRiccatiSolver.hpp:86
FeedbackArray G_
Definition: GNRiccatiSolver.hpp:83
a dummy class which is created for compatibility reasons if the MATLAB flag is not set...
Definition: matlab.hpp:17
ControlVectorArray gv_
Definition: GNRiccatiSolver.hpp:82
ct::core::FeedbackArray< STATE_DIM, CONTROL_DIM, SCALAR > FeedbackArray
Definition: GNRiccatiSolver.hpp:38
virtual void initializeAndAllocate() override
a method reserved for memory allocation (e.g. required for HPIPM)
Definition: GNRiccatiSolver-impl.hpp:286
int N_
Definition: GNRiccatiSolver.hpp:93
Eigen::SelfAdjointEigenSolver< Eigen::Matrix< SCALAR, CONTROL_DIM, CONTROL_DIM > > eigenvalueSolver_
Eigenvalue solver, used for inverting the Hessian and for regularization.
Definition: GNRiccatiSolver.hpp:98
NLOptConSettings settings_
Definition: GNRiccatiSolver.hpp:80
virtual void solveSingleStage(int N) override
Definition: GNRiccatiSolver-impl.hpp:36
StateVectorArray sv_
Definition: GNRiccatiSolver.hpp:90
Definition: LQOCSolver.hpp:22