- 3.0.2 optimal control module.
|
#include <LQOCSolver.hpp>
Public Member Functions | |
LQOCSolver (const std::shared_ptr< LQOCProblem_t > &lqocProblem=nullptr) | |
virtual | ~LQOCSolver ()=default |
void | setProblem (std::shared_ptr< LQOCProblem_t > lqocProblem) |
virtual void | configure (const NLOptConSettings &settings)=0 |
virtual bool | configureInputBoxConstraints (std::shared_ptr< LQOCProblem< STATE_DIM, CONTROL_DIM >> lqocProblem) |
setup and configure the box constraints More... | |
virtual bool | configureStateBoxConstraints (std::shared_ptr< LQOCProblem< STATE_DIM, CONTROL_DIM >> lqocProblem) |
virtual bool | configureGeneralConstraints (std::shared_ptr< LQOCProblem< STATE_DIM, CONTROL_DIM >> lqocProblem) |
setup and configure the general (in)equality constraints More... | |
virtual void | initializeAndAllocate ()=0 |
a method reserved for memory allocation (e.g. required for HPIPM) More... | |
virtual void | solve ()=0 |
solve the LQOC problem More... | |
virtual void | solveSingleStage (int N) |
virtual void | computeStatesAndControls ()=0 |
extract the solution (can be overriden if additional extraction steps required in specific solver) More... | |
const ct::core::StateVectorArray< STATE_DIM, SCALAR > & | getSolutionState () |
return solution for state More... | |
const ct::core::ControlVectorArray< CONTROL_DIM, SCALAR > & | getSolutionControl () |
return solution for control More... | |
virtual void | computeFeedbackMatrices ()=0 |
return TVLQR feedback matrices More... | |
const ct::core::FeedbackArray< STATE_DIM, CONTROL_DIM, SCALAR > & | getSolutionFeedback () |
virtual void | compute_lv ()=0 |
compute iLQR-style lv More... | |
virtual const ct::core::ControlVectorArray< CONTROL_DIM, SCALAR > & | get_lv () |
return iLQR-style feedforward lv More... | |
virtual SCALAR | getSmallestEigenvalue () |
return the smallest eigenvalue More... | |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR > | LQOCProblem_t |
Protected Member Functions | |
virtual void | setProblemImpl (std::shared_ptr< LQOCProblem_t > lqocProblem)=0 |
Protected Attributes | |
std::shared_ptr< LQOCProblem_t > | lqocProblem_ |
core::StateVectorArray< STATE_DIM, SCALAR > | x_sol_ |
core::ControlVectorArray< CONTROL_DIM, SCALAR > | u_sol_ |
ct::core::FeedbackArray< STATE_DIM, CONTROL_DIM, SCALAR > | L_ |
ct::core::ControlVectorArray< CONTROL_DIM, SCALAR > | lv_ |
Base class for solvers to solve an LQOCProblem (both constrained / unconstrained, etc.)
|
inline |
Constructor. Initialize by handing over an LQOCProblem, or otherwise by calling setProblem()
lqocProblem | shared_ptr to the LQOCProblem to be solved. |
References ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::~LQOCSolver().
|
virtualdefault |
|
inline |
set a new problem update the shared_ptr to the LQOCProblem instance and call initialize instance deriving from this class.
lqocProblem |
References ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::configure(), ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::lqocProblem_, and ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::setProblemImpl().
Referenced by TEST().
|
pure virtual |
|
inlinevirtual |
setup and configure the box constraints
|
inlinevirtual |
|
inlinevirtual |
setup and configure the general (in)equality constraints
References ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::initializeAndAllocate(), and ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::solve().
|
pure virtual |
a method reserved for memory allocation (e.g. required for HPIPM)
Implemented in ct::optcon::GNRiccatiSolver< STATE_DIM, CONTROL_DIM, SCALAR >.
Referenced by ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::configureGeneralConstraints().
|
pure virtual |
solve the LQOC problem
Implemented in ct::optcon::GNRiccatiSolver< STATE_DIM, CONTROL_DIM, SCALAR >.
Referenced by ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::configureGeneralConstraints().
|
inlinevirtual |
|
pure virtual |
extract the solution (can be overriden if additional extraction steps required in specific solver)
Implemented in ct::optcon::GNRiccatiSolver< STATE_DIM, CONTROL_DIM, SCALAR >.
Referenced by ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::solveSingleStage().
|
inline |
return solution for state
References ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::x_sol_.
Referenced by TEST().
|
inline |
return solution for control
References ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::computeFeedbackMatrices(), and ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::u_sol_.
Referenced by TEST().
|
pure virtual |
return TVLQR feedback matrices
Implemented in ct::optcon::GNRiccatiSolver< STATE_DIM, CONTROL_DIM, SCALAR >.
Referenced by ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::getSolutionControl().
|
inline |
References ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::compute_lv(), and ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::L_.
Referenced by TEST().
|
pure virtual |
compute iLQR-style lv
Implemented in ct::optcon::GNRiccatiSolver< STATE_DIM, CONTROL_DIM, SCALAR >.
Referenced by ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::getSolutionFeedback().
|
inlinevirtual |
return iLQR-style feedforward lv
References ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::lv_.
Referenced by TEST().
|
inlinevirtual |
return the smallest eigenvalue
Reimplemented in ct::optcon::GNRiccatiSolver< STATE_DIM, CONTROL_DIM, SCALAR >.
References ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::setProblemImpl().
|
protectedpure virtual |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef LQOCProblem<STATE_DIM, CONTROL_DIM, SCALAR> ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::LQOCProblem_t |
|
protected |
Referenced by ct::optcon::GNRiccatiSolver< STATE_DIM, CONTROL_DIM, SCALAR >::computeCostToGo(), ct::optcon::GNRiccatiSolver< STATE_DIM, CONTROL_DIM, SCALAR >::computeStatesAndControls(), ct::optcon::GNRiccatiSolver< STATE_DIM, CONTROL_DIM, SCALAR >::designController(), ct::optcon::GNRiccatiSolver< STATE_DIM, CONTROL_DIM, SCALAR >::initializeCostToGo(), ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::setProblem(), ct::optcon::GNRiccatiSolver< STATE_DIM, CONTROL_DIM, SCALAR >::solve(), and ct::optcon::GNRiccatiSolver< STATE_DIM, CONTROL_DIM, SCALAR >::solveSingleStage().
|
protected |
|
protected |
|
protected |
Referenced by ct::optcon::GNRiccatiSolver< STATE_DIM, CONTROL_DIM, SCALAR >::changeNumberOfStages(), ct::optcon::GNRiccatiSolver< STATE_DIM, CONTROL_DIM, SCALAR >::computeCostToGo(), ct::optcon::GNRiccatiSolver< STATE_DIM, CONTROL_DIM, SCALAR >::computeStatesAndControls(), ct::optcon::GNRiccatiSolver< STATE_DIM, CONTROL_DIM, SCALAR >::designController(), ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::getSolutionFeedback(), and ct::optcon::GNRiccatiSolver< STATE_DIM, CONTROL_DIM, SCALAR >::logToMatlab().
|
protected |
Referenced by ct::optcon::GNRiccatiSolver< STATE_DIM, CONTROL_DIM, SCALAR >::changeNumberOfStages(), ct::optcon::GNRiccatiSolver< STATE_DIM, CONTROL_DIM, SCALAR >::computeCostToGo(), ct::optcon::GNRiccatiSolver< STATE_DIM, CONTROL_DIM, SCALAR >::computeStatesAndControls(), ct::optcon::GNRiccatiSolver< STATE_DIM, CONTROL_DIM, SCALAR >::designController(), and ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::get_lv().