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

Class to solve a specfic DMS problem. More...

#include <DmsSolver.h>

Inheritance diagram for ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >:
ct::optcon::OptConSolver< DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >, DmsPolicy< STATE_DIM, CONTROL_DIM, SCALAR >, DmsSettings, STATE_DIM, CONTROL_DIM, SCALAR >

Public Types

typedef DmsDimensions< STATE_DIM, CONTROL_DIM, SCALARDIMENSIONS
 
typedef DIMENSIONS::state_vector_t state_vector_t
 
typedef DIMENSIONS::control_vector_array_t control_vector_array_t
 
typedef DIMENSIONS::control_vector_t control_vector_t
 
typedef DIMENSIONS::state_vector_array_t state_vector_array_t
 
typedef DIMENSIONS::time_array_t time_array_t
 
typedef DmsPolicy< STATE_DIM, CONTROL_DIM, SCALARPolicy_t
 
typedef ContinuousOptConProblem< STATE_DIM, CONTROL_DIM, SCALAROptConProblem_t
 
- Public Types inherited from ct::optcon::OptConSolver< DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >, DmsPolicy< STATE_DIM, CONTROL_DIM, SCALAR >, DmsSettings, STATE_DIM, CONTROL_DIM, SCALAR >
typedef DmsPolicy< STATE_DIM, CONTROL_DIM, SCALARPolicy_t
 
typedef DmsSettings Settings_t
 
typedef DmsSolver< STATE_DIM, CONTROL_DIM, SCALARDerived
 
typedef SCALAR Scalar_t
 

Public Member Functions

 DmsSolver (const ContinuousOptConProblem< STATE_DIM, CONTROL_DIM, SCALAR > problem, DmsSettings settingsDms)
 Custom constructor, converts the optcon problem to a DMS problem. More...
 
 ~DmsSolver () override=default
 Destructor. More...
 
void configure (const DmsSettings &settings) override
 
bool solve () override
 
const Policy_tgetSolution () override
 
const core::StateTrajectory< STATE_DIM, SCALARgetStateTrajectory () const override
 
const core::ControlTrajectory< CONTROL_DIM, SCALARgetControlTrajectory () const override
 
const core::tpl::TimeArray< SCALAR > & getTimeArray () const override
 
void setInitialGuess (const Policy_t &initialGuess) override
 
SCALAR getTimeHorizon () const override
 Get the time horizon the solver currently operates on. More...
 
void changeTimeHorizon (const SCALAR &tf) override
 Change the time horizon the solver operates on. More...
 
void changeInitialState (const core::StateVector< STATE_DIM, SCALAR > &x0) override
 Change the initial state for the optimal control problem. More...
 
void changeCostFunction (const typename Base::OptConProblem_t::CostFunctionPtr_t &cf) override
 
void changeNonlinearSystem (const typename Base::OptConProblem_t::DynamicsPtr_t &dyn) override
 
void changeLinearSystem (const typename Base::OptConProblem_t::LinearPtr_t &lin) override
 
void changeInputBoxConstraints (const typename Base::OptConProblem_t::ConstraintPtr_t con) override
 
void changeStateBoxConstraints (const typename Base::OptConProblem_t::ConstraintPtr_t con) override
 
void changeGeneralConstraints (const typename Base::OptConProblem_t::ConstraintPtr_t con) override
 
void printSolution ()
 Prints out the solution trajectories of the DMS problem. More...
 
std::vector< typename OptConProblem_t::DynamicsPtr_t > & getNonlinearSystemsInstances () override
 Direct accessor to the system instances. More...
 
const std::vector< typename OptConProblem_t::DynamicsPtr_t > & getNonlinearSystemsInstances () const override
 
std::vector< typename OptConProblem_t::LinearPtr_t > & getLinearSystemsInstances () override
 Direct accessor to the linear system instances. More...
 
const std::vector< typename OptConProblem_t::LinearPtr_t > & getLinearSystemsInstances () const override
 
std::vector< typename OptConProblem_t::CostFunctionPtr_t > & getCostFunctionInstances () override
 Direct accessor to the cost function instances. More...
 
const std::vector< typename OptConProblem_t::CostFunctionPtr_t > & getCostFunctionInstances () const override
 
std::vector< typename OptConProblem_t::ConstraintPtr_t > & getInputBoxConstraintsInstances () override
 Direct accessor to the box constraint instances. More...
 
const std::vector< typename OptConProblem_t::ConstraintPtr_t > & getInputBoxConstraintsInstances () const override
 
std::vector< typename OptConProblem_t::ConstraintPtr_t > & getStateBoxConstraintsInstances () override
 
const std::vector< typename OptConProblem_t::ConstraintPtr_t > & getStateBoxConstraintsInstances () const override
 
std::vector< typename OptConProblem_t::ConstraintPtr_t > & getGeneralConstraintsInstances () override
 Direct accessor to the general constraints. More...
 
const std::vector< typename OptConProblem_t::ConstraintPtr_t > & getGeneralConstraintsInstances () const override
 
- Public Member Functions inherited from ct::optcon::OptConSolver< DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >, DmsPolicy< STATE_DIM, CONTROL_DIM, SCALAR >, DmsSettings, STATE_DIM, CONTROL_DIM, SCALAR >
 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=DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR > ::SolverName)
 
virtual bool runIteration ()
 
virtual void changeCostFunction (const typename OptConProblem_t::CostFunctionPtr_t &cf)=0
 Change the cost function. More...
 
virtual void changeNonlinearSystem (const typename OptConProblem_t::DynamicsPtr_t &dyn)=0
 Change the nonlinear system. More...
 
virtual void changeLinearSystem (const typename OptConProblem_t::LinearPtr_t &lin)=0
 Change the linear system. More...
 
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 SCALAR getCost () const
 
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...
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef OptConSolver< DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >, DmsPolicy< STATE_DIM, CONTROL_DIM, SCALAR >, DmsSettings, STATE_DIM, CONTROL_DIM > Base
 
- Public Attributes inherited from ct::optcon::OptConSolver< DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >, DmsPolicy< STATE_DIM, CONTROL_DIM, SCALAR >, DmsSettings, STATE_DIM, CONTROL_DIM, SCALAR >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef std::conditional< true, ContinuousOptConProblem< STATE_DIM, CONTROL_DIM, SCALAR >, DiscreteOptConProblem< STATE_DIM, CONTROL_DIM, SCALAR > >::type OptConProblem_t
 

Additional Inherited Members

- Static Public Attributes inherited from ct::optcon::OptConSolver< DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >, DmsPolicy< STATE_DIM, CONTROL_DIM, SCALAR >, DmsSettings, STATE_DIM, CONTROL_DIM, SCALAR >
static const size_t STATE_D
 
static const size_t CONTROL_D
 

Detailed Description

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

Class to solve a specfic DMS problem.

An example employing different DMS solvers is given in unit test oscDMSTest.cpp

Template Parameters
STATE_DIMThe state dimension
CONTROL_DIMThe control dimension
Examples:
DMS.cpp.

Member Typedef Documentation

◆ DIMENSIONS

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
typedef DmsDimensions<STATE_DIM, CONTROL_DIM, SCALAR> ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::DIMENSIONS

◆ state_vector_t

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
typedef DIMENSIONS::state_vector_t ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::state_vector_t

◆ control_vector_array_t

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
typedef DIMENSIONS::control_vector_array_t ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::control_vector_array_t

◆ control_vector_t

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
typedef DIMENSIONS::control_vector_t ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::control_vector_t

◆ state_vector_array_t

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
typedef DIMENSIONS::state_vector_array_t ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::state_vector_array_t

◆ time_array_t

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
typedef DIMENSIONS::time_array_t ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::time_array_t

◆ Policy_t

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
typedef DmsPolicy<STATE_DIM, CONTROL_DIM, SCALAR> ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::Policy_t

◆ OptConProblem_t

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
typedef ContinuousOptConProblem<STATE_DIM, CONTROL_DIM, SCALAR> ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::OptConProblem_t

Constructor & Destructor Documentation

◆ DmsSolver()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::DmsSolver ( const ContinuousOptConProblem< STATE_DIM, CONTROL_DIM, SCALAR problem,
DmsSettings  settingsDms 
)
inline

Custom constructor, converts the optcon problem to a DMS problem.

Parameters
[in]problemThe optimal control problem
[in]settingsDmsThe dms settings

References ct::optcon::IPOPT, and ct::optcon::SNOPT.

◆ ~DmsSolver()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::~DmsSolver ( )
overridedefault

Destructor.

Member Function Documentation

◆ configure()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
void ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::configure ( const DmsSettings settings)
inlineoverridevirtual

◆ solve()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
bool ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::solve ( )
inlineoverridevirtual

◆ getSolution()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
const Policy_t& ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::getSolution ( )
inlineoverridevirtual

◆ getStateTrajectory()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
const core::StateTrajectory<STATE_DIM, SCALAR> ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::getStateTrajectory ( ) const
inlineoverridevirtual

◆ getControlTrajectory()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
const core::ControlTrajectory<CONTROL_DIM, SCALAR> ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::getControlTrajectory ( ) const
inlineoverridevirtual

◆ getTimeArray()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
const core::tpl::TimeArray<SCALAR>& ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::getTimeArray ( ) const
inlineoverridevirtual

◆ setInitialGuess()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
void ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::setInitialGuess ( const Policy_t initialGuess)
inlineoverridevirtual

◆ getTimeHorizon()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
SCALAR ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::getTimeHorizon ( ) const
inlineoverridevirtual

◆ changeTimeHorizon()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
void ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::changeTimeHorizon ( const SCALAR tf)
inlineoverridevirtual

Change the time horizon the solver operates on.

This function does not need to be called if setProblem() has been called with an OptConProblem that had the correct time horizon set.

Implements ct::optcon::OptConSolver< DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >, DmsPolicy< STATE_DIM, CONTROL_DIM, SCALAR >, DmsSettings, STATE_DIM, CONTROL_DIM, SCALAR >.

◆ changeInitialState()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
void ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::changeInitialState ( const core::StateVector< STATE_DIM, SCALAR > &  x0)
inlineoverridevirtual

Change the initial state for the optimal control problem.

This function does not need to be called if setProblem() has been called with an OptConProblem that had the correct initial state set

Implements ct::optcon::OptConSolver< DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >, DmsPolicy< STATE_DIM, CONTROL_DIM, SCALAR >, DmsSettings, STATE_DIM, CONTROL_DIM, SCALAR >.

References x0.

◆ changeCostFunction()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
void ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::changeCostFunction ( const typename Base::OptConProblem_t::CostFunctionPtr_t &  cf)
inlineoverride

References i.

◆ changeNonlinearSystem()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
void ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::changeNonlinearSystem ( const typename Base::OptConProblem_t::DynamicsPtr_t &  dyn)
inlineoverride

References i.

◆ changeLinearSystem()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
void ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::changeLinearSystem ( const typename Base::OptConProblem_t::LinearPtr_t &  lin)
inlineoverride

References i.

◆ changeInputBoxConstraints()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
void ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::changeInputBoxConstraints ( const typename Base::OptConProblem_t::ConstraintPtr_t  con)
inlineoverride

◆ changeStateBoxConstraints()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
void ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::changeStateBoxConstraints ( const typename Base::OptConProblem_t::ConstraintPtr_t  con)
inlineoverride

◆ changeGeneralConstraints()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
void ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::changeGeneralConstraints ( const typename Base::OptConProblem_t::ConstraintPtr_t  con)
inlineoverride

◆ printSolution()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
void ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::printSolution ( )
inline

Prints out the solution trajectories of the DMS problem.

◆ getNonlinearSystemsInstances() [1/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
std::vector<typename OptConProblem_t::DynamicsPtr_t>& ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::getNonlinearSystemsInstances ( )
inlineoverridevirtual

Direct accessor to the system instances.

Warning
{Use this only when performance absolutely matters and if you know what you are doing. Otherwise use e.g. changeNonlinearSystem() to change the system dynamics in a safe and easy way. You should especially not change the size of the vector or modify each entry differently.}
Returns

Implements ct::optcon::OptConSolver< DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >, DmsPolicy< STATE_DIM, CONTROL_DIM, SCALAR >, DmsSettings, STATE_DIM, CONTROL_DIM, SCALAR >.

◆ getNonlinearSystemsInstances() [2/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
const std::vector<typename OptConProblem_t::DynamicsPtr_t>& ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::getNonlinearSystemsInstances ( ) const
inlineoverridevirtual

◆ getLinearSystemsInstances() [1/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
std::vector<typename OptConProblem_t::LinearPtr_t>& ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::getLinearSystemsInstances ( )
inlineoverridevirtual

Direct accessor to the linear system instances.

Warning
{Use this only when performance absolutely matters and if you know what you are doing. Otherwise use e.g. changeLinearSystem() to change the system dynamics in a safe and easy way. You should especially not change the size of the vector or modify each entry differently.}
Returns

Implements ct::optcon::OptConSolver< DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >, DmsPolicy< STATE_DIM, CONTROL_DIM, SCALAR >, DmsSettings, STATE_DIM, CONTROL_DIM, SCALAR >.

◆ getLinearSystemsInstances() [2/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
const std::vector<typename OptConProblem_t::LinearPtr_t>& ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::getLinearSystemsInstances ( ) const
inlineoverridevirtual

◆ getCostFunctionInstances() [1/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
std::vector<typename OptConProblem_t::CostFunctionPtr_t>& ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::getCostFunctionInstances ( )
inlineoverridevirtual

Direct accessor to the cost function instances.

Warning
{Use this only when performance absolutely matters and if you know what you are doing. Otherwise use e.g. changeCostFunction() to change the system dynamics in a safe and easy way. You should especially not change the size of the vector or modify each entry differently.}
Returns

Implements ct::optcon::OptConSolver< DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >, DmsPolicy< STATE_DIM, CONTROL_DIM, SCALAR >, DmsSettings, STATE_DIM, CONTROL_DIM, SCALAR >.

◆ getCostFunctionInstances() [2/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
const std::vector<typename OptConProblem_t::CostFunctionPtr_t>& ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::getCostFunctionInstances ( ) const
inlineoverridevirtual

◆ getInputBoxConstraintsInstances() [1/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
std::vector<typename OptConProblem_t::ConstraintPtr_t>& ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::getInputBoxConstraintsInstances ( )
inlineoverridevirtual

Direct accessor to the box constraint instances.

Warning
{Use this only when performance absolutely matters and if you know what you are doing. Otherwise use e.g. changeCostFunction() to change the system dynamics in a safe and easy way. You should especially not change the size of the vector or modify each entry differently.}
Returns
The state box constraint instances

Reimplemented from ct::optcon::OptConSolver< DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >, DmsPolicy< STATE_DIM, CONTROL_DIM, SCALAR >, DmsSettings, STATE_DIM, CONTROL_DIM, SCALAR >.

◆ getInputBoxConstraintsInstances() [2/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
const std::vector<typename OptConProblem_t::ConstraintPtr_t>& ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::getInputBoxConstraintsInstances ( ) const
inlineoverridevirtual

◆ getStateBoxConstraintsInstances() [1/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
std::vector<typename OptConProblem_t::ConstraintPtr_t>& ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::getStateBoxConstraintsInstances ( )
inlineoverridevirtual

◆ getStateBoxConstraintsInstances() [2/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
const std::vector<typename OptConProblem_t::ConstraintPtr_t>& ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::getStateBoxConstraintsInstances ( ) const
inlineoverridevirtual

◆ getGeneralConstraintsInstances() [1/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
std::vector<typename OptConProblem_t::ConstraintPtr_t>& ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::getGeneralConstraintsInstances ( )
inlineoverridevirtual

Direct accessor to the general constraints.

Warning
{Use this only when performance absolutely matters and if you know what you are doing. Otherwise use e.g. changeCostFunction() to change the system dynamics in a safe and easy way. You should especially not change the size of the vector or modify each entry differently.}
Returns
The general constraints instances.

Reimplemented from ct::optcon::OptConSolver< DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >, DmsPolicy< STATE_DIM, CONTROL_DIM, SCALAR >, DmsSettings, STATE_DIM, CONTROL_DIM, SCALAR >.

◆ getGeneralConstraintsInstances() [2/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
const std::vector<typename OptConProblem_t::ConstraintPtr_t>& ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::getGeneralConstraintsInstances ( ) const
inlineoverridevirtual

Member Data Documentation

◆ Base

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef OptConSolver<DmsSolver<STATE_DIM, CONTROL_DIM, SCALAR>, DmsPolicy<STATE_DIM, CONTROL_DIM, SCALAR>, DmsSettings, STATE_DIM, CONTROL_DIM> ct::optcon::DmsSolver< STATE_DIM, CONTROL_DIM, SCALAR >::Base

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