- 3.0.2 optimal control module.
ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS > Class Template Referencefinal

#include <NLOptConSolver.hpp>

Inheritance diagram for ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >:
ct::optcon::OptConSolver< NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >, NLOCAlgorithm< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::Policy_t, NLOptConSettings, STATE_DIM, CONTROL_DIM, SCALAR, CONTINUOUS >

Public Types

typedef OptConSolver< NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >, typename NLOCAlgorithm< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::Policy_t, NLOptConSettings, STATE_DIM, CONTROL_DIM, SCALAR, CONTINUOUS > Base
 
typedef NLOptConSettings Settings_t
 
typedef SCALAR Scalar_t
 
typedef Base::OptConProblem_t OptConProblem_t
 
typedef NLOCAlgorithm< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS > NLOCAlgorithm_t
 
typedef NLOCAlgorithm_t::Policy_t Policy_t
 
typedef NLOCAlgorithm_t::Backend_t Backend_t
 
- Public Types inherited from ct::optcon::OptConSolver< NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >, NLOCAlgorithm< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::Policy_t, NLOptConSettings, STATE_DIM, CONTROL_DIM, SCALAR, CONTINUOUS >
typedef NLOCAlgorithm< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::Policy_t Policy_t
 
typedef NLOptConSettings Settings_t
 
typedef NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS > Derived
 
typedef SCALAR Scalar_t
 

Public Member Functions

 NLOptConSolver (const OptConProblem_t &optConProblem, const Settings_t &settings)
 constructor More...
 
 NLOptConSolver (const OptConProblem_t &optConProblem, const std::string &settingsFile, bool verbose=true, const std::string &ns="alg")
 constructor More...
 
virtual ~NLOptConSolver ()=default
 destructor More...
 
void initialize (const OptConProblem_t &optConProblem, const Settings_t &settings)
 
void configure (const Settings_t &settings) override
 
virtual void prepareIteration ()
 
virtual bool finishIteration ()
 
virtual void prepareMPCIteration ()
 
virtual bool finishMPCIteration ()
 
virtual bool runIteration () override
 
void setInitialGuess (const Policy_t &initialGuess) override
 
virtual bool solve () override
 
virtual const Policy_tgetSolution () override
 
virtual const core::StateTrajectory< STATE_DIM, SCALARgetStateTrajectory () const override
 
virtual const core::ControlTrajectory< CONTROL_DIM, SCALARgetControlTrajectory () const override
 
virtual const core::tpl::TimeArray< SCALAR > & getTimeArray () const override
 
virtual SCALAR getTimeHorizon () const override
 Get the time horizon the solver currently operates on. More...
 
virtual void changeTimeHorizon (const SCALAR &tf) override
 Change the time horizon the solver operates on. More...
 
virtual void changeInitialState (const core::StateVector< STATE_DIM, SCALAR > &x0) override
 Change the initial state for the optimal control problem. More...
 
virtual void changeCostFunction (const typename OptConProblem_t::CostFunctionPtr_t &cf) override
 Change the cost function. More...
 
virtual void changeNonlinearSystem (const typename OptConProblem_t::DynamicsPtr_t &dyn) override
 Change the nonlinear system. More...
 
virtual void changeLinearSystem (const typename OptConProblem_t::LinearPtr_t &lin) override
 Change the linear system. More...
 
virtual SCALAR getCost () const override
 
const Settings_tgetSettings ()
 get a reference to the current settings More...
 
const std::shared_ptr< Backend_t > & getBackend ()
 get a reference to the backend ( More...
 
std::vector< typename OptConProblem_t::DynamicsPtr_t > & getNonlinearSystemsInstances () override
 get reference to the nonlinear system More...
 
const std::vector< typename OptConProblem_t::DynamicsPtr_t > & getNonlinearSystemsInstances () const override
 get constant reference to the nonlinear system More...
 
std::vector< typename OptConProblem_t::LinearPtr_t > & getLinearSystemsInstances () override
 get reference to the linearized system More...
 
const std::vector< typename OptConProblem_t::LinearPtr_t > & getLinearSystemsInstances () const override
 get constant reference to the linearized system More...
 
std::vector< typename OptConProblem_t::CostFunctionPtr_t > & getCostFunctionInstances () override
 get reference to the cost function More...
 
const std::vector< typename OptConProblem_t::CostFunctionPtr_t > & getCostFunctionInstances () const override
 get constant reference to the cost function More...
 
std::vector< typename OptConProblem_t::ConstraintPtr_t > & getInputBoxConstraintsInstances () override
 get reference to the box constraints More...
 
const std::vector< typename OptConProblem_t::ConstraintPtr_t > & getInputBoxConstraintsInstances () const override
 get constant reference to the boxconstraints More...
 
std::vector< typename OptConProblem_t::ConstraintPtr_t > & getStateBoxConstraintsInstances () override
 get reference to the box constraints More...
 
const std::vector< typename OptConProblem_t::ConstraintPtr_t > & getStateBoxConstraintsInstances () const override
 get constant reference to the boxconstraints More...
 
std::vector< typename OptConProblem_t::ConstraintPtr_t > & getGeneralConstraintsInstances () override
 get reference to the general constraints More...
 
const std::vector< typename OptConProblem_t::ConstraintPtr_t > & getGeneralConstraintsInstances () const override
 get constant reference to the general constraints More...
 
void logSummaryToMatlab (const std::string &fileName)
 logging a short summary to matlab More...
 
- Public Member Functions inherited from ct::optcon::OptConSolver< NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >, NLOCAlgorithm< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::Policy_t, NLOptConSettings, STATE_DIM, CONTROL_DIM, SCALAR, CONTINUOUS >
 OptConSolver ()
 
virtual ~OptConSolver ()
 
virtual void setProblem (const OptConProblem_t &optConProblem)
 Assigns the optimal control problem to the solver. More...
 
void configureFromFile (const std::string &filename, bool verbose=true, const std::string &ns=NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS > ::SolverName)
 
virtual void setInitialGuess (const Policy_t &initialGuess)=0
 
virtual void changeInputBoxConstraints (const typename OptConProblem_t::ConstraintPtr_t con)
 Change the box constraints. More...
 
virtual void changeStateBoxConstraints (const typename OptConProblem_t::ConstraintPtr_t con)
 
virtual void changeGeneralConstraints (const typename OptConProblem_t::ConstraintPtr_t con)
 Change the general constraints. More...
 
virtual void generateCode (const ct::core::DerivativesCppadSettings &settings)
 Generates source AD source code which can be used in the solver. This method needs to be called ahead of actually solving the problem (e.g. from a different executable) More...
 

Static Public Attributes

static EIGEN_MAKE_ALIGNED_OPERATOR_NEW const size_t STATE_D = STATE_DIM
 
static const size_t CONTROL_D = CONTROL_DIM
 
static const size_t POS_DIM = P_DIM
 
static const size_t VEL_DIM = V_DIM
 
- Static Public Attributes inherited from ct::optcon::OptConSolver< NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >, NLOCAlgorithm< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::Policy_t, NLOptConSettings, STATE_DIM, CONTROL_DIM, SCALAR, CONTINUOUS >
static const size_t STATE_D
 
static const size_t CONTROL_D
 

Protected Attributes

std::shared_ptr< Backend_tnlocBackend_
 the backend holding all the math operations More...
 
std::shared_ptr< NLOCAlgorithm_tnlocAlgorithm_
 the algorithm for sequencing the math operations in correct manner More...
 

Additional Inherited Members

- Public Attributes inherited from ct::optcon::OptConSolver< NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >, NLOCAlgorithm< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::Policy_t, NLOptConSettings, STATE_DIM, CONTROL_DIM, SCALAR, CONTINUOUS >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef std::conditional< CONTINUOUS, ContinuousOptConProblem< STATE_DIM, CONTROL_DIM, SCALAR >, DiscreteOptConProblem< STATE_DIM, CONTROL_DIM, SCALAR > >::type OptConProblem_t
 

Detailed Description

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM = STATE_DIM / 2, size_t V_DIM = STATE_DIM / 2, typename SCALAR = double, bool CONTINUOUS = true>
class ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >

Examples:
LinearSystemTest.h, NLOC.cpp, NLOC_boxConstrained.cpp, NLOC_generalConstrained.cpp, NLOC_MPC.cpp, NonlinearSystemTest.h, switched_continuous_optcon.cpp, and SymplecticTest.h.

Member Typedef Documentation

◆ Base

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM = STATE_DIM / 2, size_t V_DIM = STATE_DIM / 2, typename SCALAR = double, bool CONTINUOUS = true>
typedef OptConSolver<NLOptConSolver<STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS>, typename NLOCAlgorithm<STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS>::Policy_t, NLOptConSettings, STATE_DIM, CONTROL_DIM, SCALAR, CONTINUOUS> ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::Base

◆ Settings_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM = STATE_DIM / 2, size_t V_DIM = STATE_DIM / 2, typename SCALAR = double, bool CONTINUOUS = true>
typedef NLOptConSettings ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::Settings_t

◆ Scalar_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM = STATE_DIM / 2, size_t V_DIM = STATE_DIM / 2, typename SCALAR = double, bool CONTINUOUS = true>
typedef SCALAR ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::Scalar_t

◆ OptConProblem_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM = STATE_DIM / 2, size_t V_DIM = STATE_DIM / 2, typename SCALAR = double, bool CONTINUOUS = true>
typedef Base::OptConProblem_t ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t

◆ NLOCAlgorithm_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM = STATE_DIM / 2, size_t V_DIM = STATE_DIM / 2, typename SCALAR = double, bool CONTINUOUS = true>
typedef NLOCAlgorithm<STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS> ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::NLOCAlgorithm_t

◆ Policy_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM = STATE_DIM / 2, size_t V_DIM = STATE_DIM / 2, typename SCALAR = double, bool CONTINUOUS = true>
typedef NLOCAlgorithm_t::Policy_t ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::Policy_t

◆ Backend_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM = STATE_DIM / 2, size_t V_DIM = STATE_DIM / 2, typename SCALAR = double, bool CONTINUOUS = true>
typedef NLOCAlgorithm_t::Backend_t ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::Backend_t

Constructor & Destructor Documentation

◆ NLOptConSolver() [1/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::NLOptConSolver ( const OptConProblem_t optConProblem,
const Settings_t settings 
)

constructor

◆ NLOptConSolver() [2/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::NLOptConSolver ( const OptConProblem_t optConProblem,
const std::string &  settingsFile,
bool  verbose = true,
const std::string &  ns = "alg" 
)

◆ ~NLOptConSolver()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM = STATE_DIM / 2, size_t V_DIM = STATE_DIM / 2, typename SCALAR = double, bool CONTINUOUS = true>
virtual ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::~NLOptConSolver ( )
virtualdefault

destructor

Member Function Documentation

◆ initialize()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::initialize ( const OptConProblem_t optConProblem,
const Settings_t settings 
)

◆ configure()

◆ prepareIteration()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::prepareIteration ( )
virtual

execute preparation steps for an iteration, e.g. computation of defects

References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocAlgorithm_.

◆ finishIteration()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
bool ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::finishIteration ( )
virtual

execute finishing step for an iteration, e.g. solving Riccati backward pass.

Returns

References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocAlgorithm_.

◆ prepareMPCIteration()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::prepareMPCIteration ( )
virtual

execute preparation steps for an iteration, e.g. computation of defects

References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocAlgorithm_.

◆ finishMPCIteration()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
bool ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::finishMPCIteration ( )
virtual

execute finishing step for an iteration, e.g. solving Riccati backward pass.

Returns

References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocAlgorithm_.

◆ runIteration()

◆ setInitialGuess()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::setInitialGuess ( const Policy_t initialGuess)
override

◆ solve()

◆ getSolution()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
const NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::Policy_t & ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getSolution ( )
overridevirtual

◆ getStateTrajectory()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
const core::StateTrajectory< STATE_DIM, SCALAR > ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getStateTrajectory ( ) const
overridevirtual

◆ getControlTrajectory()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
const core::ControlTrajectory< CONTROL_DIM, SCALAR > ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getControlTrajectory ( ) const
overridevirtual

◆ getTimeArray()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
const core::tpl::TimeArray< SCALAR > & ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getTimeArray ( ) const
overridevirtual

◆ getTimeHorizon()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
SCALAR ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getTimeHorizon ( ) const
overridevirtual

◆ changeTimeHorizon()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeTimeHorizon ( const SCALAR tf)
overridevirtual

◆ changeInitialState()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeInitialState ( const core::StateVector< STATE_DIM, SCALAR > &  x0)
overridevirtual

◆ changeCostFunction()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeCostFunction ( const typename OptConProblem_t::CostFunctionPtr_t &  cf)
overridevirtual

◆ changeNonlinearSystem()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeNonlinearSystem ( const typename OptConProblem_t::DynamicsPtr_t &  dyn)
overridevirtual

◆ changeLinearSystem()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeLinearSystem ( const typename OptConProblem_t::LinearPtr_t &  lin)
overridevirtual

◆ getCost()

◆ getSettings()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
const NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::Settings_t & ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getSettings ( )

◆ getBackend()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
const std::shared_ptr< typename NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::Backend_t > & ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getBackend ( )

get a reference to the backend (

Todo:
this is not optimal, allows the user too much access)
Examples:
LinearSystemTest.h.

References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.

Referenced by ct::optcon::example::TEST().

◆ getNonlinearSystemsInstances() [1/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
std::vector< typename NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t::DynamicsPtr_t > & ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getNonlinearSystemsInstances ( )
overridevirtual

◆ getNonlinearSystemsInstances() [2/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
const std::vector< typename NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t::DynamicsPtr_t > & ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getNonlinearSystemsInstances ( ) const
overridevirtual

◆ getLinearSystemsInstances() [1/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
std::vector< typename NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t::LinearPtr_t > & ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getLinearSystemsInstances ( )
overridevirtual

◆ getLinearSystemsInstances() [2/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
const std::vector< typename NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t::LinearPtr_t > & ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getLinearSystemsInstances ( ) const
overridevirtual

◆ getCostFunctionInstances() [1/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
std::vector< typename NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t::CostFunctionPtr_t > & ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getCostFunctionInstances ( )
overridevirtual

◆ getCostFunctionInstances() [2/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
const std::vector< typename NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t::CostFunctionPtr_t > & ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getCostFunctionInstances ( ) const
overridevirtual

◆ getInputBoxConstraintsInstances() [1/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
std::vector< typename NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t::ConstraintPtr_t > & ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getInputBoxConstraintsInstances ( )
overridevirtual

◆ getInputBoxConstraintsInstances() [2/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
const std::vector< typename NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t::ConstraintPtr_t > & ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getInputBoxConstraintsInstances ( ) const
overridevirtual

◆ getStateBoxConstraintsInstances() [1/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
std::vector< typename NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t::ConstraintPtr_t > & ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getStateBoxConstraintsInstances ( )
overridevirtual

◆ getStateBoxConstraintsInstances() [2/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
const std::vector< typename NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t::ConstraintPtr_t > & ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getStateBoxConstraintsInstances ( ) const
overridevirtual

◆ getGeneralConstraintsInstances() [1/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
std::vector< typename NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t::ConstraintPtr_t > & ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getGeneralConstraintsInstances ( )
overridevirtual

◆ getGeneralConstraintsInstances() [2/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
const std::vector< typename NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t::ConstraintPtr_t > & ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getGeneralConstraintsInstances ( ) const
overridevirtual

◆ logSummaryToMatlab()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::logSummaryToMatlab ( const std::string &  fileName)

Member Data Documentation

◆ STATE_D

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM = STATE_DIM / 2, size_t V_DIM = STATE_DIM / 2, typename SCALAR = double, bool CONTINUOUS = true>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW const size_t ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::STATE_D = STATE_DIM
static

◆ CONTROL_D

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM = STATE_DIM / 2, size_t V_DIM = STATE_DIM / 2, typename SCALAR = double, bool CONTINUOUS = true>
const size_t ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::CONTROL_D = CONTROL_DIM
static

◆ POS_DIM

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM = STATE_DIM / 2, size_t V_DIM = STATE_DIM / 2, typename SCALAR = double, bool CONTINUOUS = true>
const size_t ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::POS_DIM = P_DIM
static

◆ VEL_DIM

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM = STATE_DIM / 2, size_t V_DIM = STATE_DIM / 2, typename SCALAR = double, bool CONTINUOUS = true>
const size_t ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::VEL_DIM = V_DIM
static

◆ nlocBackend_

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM = STATE_DIM / 2, size_t V_DIM = STATE_DIM / 2, typename SCALAR = double, bool CONTINUOUS = true>
std::shared_ptr<Backend_t> ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_
protected

the backend holding all the math operations

Referenced by ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeCostFunction(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeInitialState(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeLinearSystem(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeNonlinearSystem(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeTimeHorizon(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::configure(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getBackend(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getControlTrajectory(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getCost(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getCostFunctionInstances(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getGeneralConstraintsInstances(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getInputBoxConstraintsInstances(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getLinearSystemsInstances(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getNonlinearSystemsInstances(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getSettings(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getSolution(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getStateBoxConstraintsInstances(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getStateTrajectory(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getTimeArray(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getTimeHorizon(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::initialize(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::logSummaryToMatlab(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::NLOptConSolver(), and ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::setInitialGuess().

◆ nlocAlgorithm_


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