- 3.0.2 optimal control module.
ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR > Class Template Referenceabstract

#include <LQOCSolver.hpp>

Inheritance diagram for ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >:
ct::optcon::GNRiccatiSolver< STATE_DIM, CONTROL_DIM, SCALAR >

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, SCALARLQOCProblem_t
 

Protected Member Functions

virtual void setProblemImpl (std::shared_ptr< LQOCProblem_t > lqocProblem)=0
 

Protected Attributes

std::shared_ptr< LQOCProblem_tlqocProblem_
 
core::StateVectorArray< STATE_DIM, SCALARx_sol_
 
core::ControlVectorArray< CONTROL_DIM, SCALARu_sol_
 
ct::core::FeedbackArray< STATE_DIM, CONTROL_DIM, SCALARL_
 
ct::core::ControlVectorArray< CONTROL_DIM, SCALARlv_
 

Detailed Description

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
class ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >

Base class for solvers to solve an LQOCProblem (both constrained / unconstrained, etc.)

Todo:
uncouple from NLOptConSettings

Constructor & Destructor Documentation

◆ LQOCSolver()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::LQOCSolver ( const std::shared_ptr< LQOCProblem_t > &  lqocProblem = nullptr)
inline

Constructor. Initialize by handing over an LQOCProblem, or otherwise by calling setProblem()

Parameters
lqocProblemshared_ptr to the LQOCProblem to be solved.

References ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::~LQOCSolver().

◆ ~LQOCSolver()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
virtual ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::~LQOCSolver ( )
virtualdefault

Member Function Documentation

◆ setProblem()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
void ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::setProblem ( std::shared_ptr< LQOCProblem_t lqocProblem)
inline

set a new problem update the shared_ptr to the LQOCProblem instance and call initialize instance deriving from this class.

Parameters
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().

◆ configure()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
virtual void ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::configure ( const NLOptConSettings settings)
pure virtual

◆ configureInputBoxConstraints()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
virtual bool ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::configureInputBoxConstraints ( std::shared_ptr< LQOCProblem< STATE_DIM, CONTROL_DIM >>  lqocProblem)
inlinevirtual

setup and configure the box constraints

◆ configureStateBoxConstraints()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
virtual bool ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::configureStateBoxConstraints ( std::shared_ptr< LQOCProblem< STATE_DIM, CONTROL_DIM >>  lqocProblem)
inlinevirtual

◆ configureGeneralConstraints()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
virtual bool ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::configureGeneralConstraints ( std::shared_ptr< LQOCProblem< STATE_DIM, CONTROL_DIM >>  lqocProblem)
inlinevirtual

◆ initializeAndAllocate()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
virtual void ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::initializeAndAllocate ( )
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().

◆ solve()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
virtual void ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::solve ( )
pure virtual

◆ solveSingleStage()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
virtual void ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::solveSingleStage ( int  N)
inlinevirtual

◆ computeStatesAndControls()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
virtual void ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::computeStatesAndControls ( )
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().

◆ getSolutionState()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
const ct::core::StateVectorArray<STATE_DIM, SCALAR>& ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::getSolutionState ( )
inline

return solution for state

References ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::x_sol_.

Referenced by TEST().

◆ getSolutionControl()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
const ct::core::ControlVectorArray<CONTROL_DIM, SCALAR>& ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::getSolutionControl ( )
inline

◆ computeFeedbackMatrices()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
virtual void ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::computeFeedbackMatrices ( )
pure virtual

◆ getSolutionFeedback()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
const ct::core::FeedbackArray<STATE_DIM, CONTROL_DIM, SCALAR>& ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::getSolutionFeedback ( )
inline

◆ compute_lv()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
virtual void ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::compute_lv ( )
pure virtual

◆ get_lv()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
virtual const ct::core::ControlVectorArray<CONTROL_DIM, SCALAR>& ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::get_lv ( )
inlinevirtual

return iLQR-style feedforward lv

References ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::lv_.

Referenced by TEST().

◆ getSmallestEigenvalue()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
virtual SCALAR ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::getSmallestEigenvalue ( )
inlinevirtual

◆ setProblemImpl()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
virtual void ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::setProblemImpl ( std::shared_ptr< LQOCProblem_t lqocProblem)
protectedpure virtual

Member Data Documentation

◆ LQOCProblem_t

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef LQOCProblem<STATE_DIM, CONTROL_DIM, SCALAR> ct::optcon::LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR >::LQOCProblem_t

◆ lqocProblem_

◆ x_sol_

◆ u_sol_

◆ L_

◆ lv_


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