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

This class sets up the DMS problem. More...

#include <DmsProblem.h>

Inheritance diagram for ct::optcon::DmsProblem< STATE_DIM, CONTROL_DIM, SCALAR >:
ct::optcon::tpl::Nlp< SCALAR >

Public Types

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 ContinuousOptConProblem< STATE_DIM, CONTROL_DIM, SCALAROptConProblem_t
 
- Public Types inherited from ct::optcon::tpl::Nlp< SCALAR >
using VectorXs = Eigen::Matrix< SCALAR, Eigen::Dynamic, 1 >
 
using VectorXi = Eigen::Matrix< int, Eigen::Dynamic, 1 >
 
using MapVecXs = Eigen::Map< VectorXs >
 
using MapVecXi = Eigen::Map< VectorXi >
 
using MapConstVecXs = Eigen::Map< const VectorXs >
 

Public Member Functions

 DmsProblem (DmsSettings settings, std::vector< typename OptConProblem_t::DynamicsPtr_t > systemPtrs, std::vector< typename OptConProblem_t::LinearPtr_t > linearPtrs, std::vector< typename OptConProblem_t::CostFunctionPtr_t > costPtrs, std::vector< typename OptConProblem_t::ConstraintPtr_t > inputBoxConstraints, std::vector< typename OptConProblem_t::ConstraintPtr_t > stateBoxConstraints, std::vector< typename OptConProblem_t::ConstraintPtr_t > generalConstraints, const state_vector_t &x0)
 Custom constructor, sets up the objects needed for the Dms algorithm depending on the settings. More...
 
 ~DmsProblem () override=default
 Destructor. More...
 
void updateProblem () override
 { This method gets called at each update of the Optimization variables. This can be used to distribute or rearrange the optimization variables appropriately } More...
 
void configure (const DmsSettings &settings)
 Updates the settings. More...
 
const state_vector_array_tgetStateSolution ()
 Retrieves the solution state trajectory at every shot. More...
 
const control_vector_array_tgetInputSolution ()
 Retrieves the solution control trajectory at every shot. More...
 
const time_array_tgetTimeSolution ()
 Retrieves the solution time trajectory at every shot. More...
 
const state_vector_array_tgetStateTrajectory ()
 Retrieves a dense state solution trajectory. More...
 
const control_vector_array_tgetInputTrajectory ()
 Retrieves a dense input solution trajectory. More...
 
const time_array_tgetTimeArray ()
 Retrieves a dense time solution trajectory. More...
 
void setInitialGuess (const state_vector_array_t &x_init_guess, const control_vector_array_t &u_init_guess, const time_array_t &t_init_guess=time_array_t(0.0))
 Sets the initial guess of the optimization. More...
 
const core::Time getTimeHorizon () const
 Return the timehorizon of the problem. More...
 
void changeTimeHorizon (const SCALAR tf)
 Updates the timehorizon. More...
 
void changeInitialState (const state_vector_t &x0)
 Updates the initial state. More...
 
void printSolution ()
 Prints the solution trajectories. More...
 
- Public Member Functions inherited from ct::optcon::tpl::Nlp< SCALAR >
 Nlp ()=default
 Default constructor. More...
 
virtual ~Nlp ()=default
 Destructor. More...
 
SCALAR evaluateCostFun ()
 { Evaluates the costfunction at the current nlp iteration } More...
 
void evaluateCostGradient (const size_t n, MapVecXs &grad)
 { Evaluates the gradient of the costfunction} More...
 
void evaluateConstraints (MapVecXs &values)
 { Evaluates the constraints } More...
 
void evaluateConstraintJacobian (const int nele_jac, MapVecXs &jac)
 { Evaluates the constraint jacobian } More...
 
void evaluateHessian (const int nele_hes, MapVecXs &hes, const SCALAR obj_fac, MapConstVecXs &lambda)
 Evaluates the hessian of the lagrangian. More...
 
void getSparsityPatternJacobian (const int nele_jac, MapVecXi &iRow, MapVecXi &jCol) const
 Gets the sparsity pattern. More...
 
void getSparsityPatternHessian (const int nele_hes, MapVecXi &iRow, MapVecXi &jCol) const
 Gets the sparsity pattern of the Hessian of the Lagrangian. More...
 
size_t getConstraintsCount () const
 Returns the number of constraints in the NLP. More...
 
size_t getNonZeroJacobianCount () const
 Returns the number of the non zero elements of the constraint jacobian. More...
 
size_t getNonZeroHessianCount ()
 Returns the number of non zeros in the Hessian. More...
 
void getConstraintBounds (MapVecXs &lowerBound, MapVecXs &upperBound, const size_t m) const
 Reads the bounds of the constraints. More...
 
size_t getVarCount () const
 Returns the number of Optimization optimization variables. More...
 
void getVariableBounds (MapVecXs &lowerBound, MapVecXs &upperBound, const size_t n) const
 Reads the bounds on the Optimization optimization variables. More...
 
void extractOptimizationVars (const MapConstVecXs &x, bool isNew)
 {Extracts the Optimization optimization variables from the nlp solvers between nlp iterations} More...
 
void getInitialGuess (const size_t n, MapVecXs &x) const
 Gets the Optimization variables. More...
 
void getOptimizationMultState (const size_t n, MapVecXs &xMul, MapVecXi &xState) const
 Gets the variable multiplier and the variable state, used in the NLP solver SNOPT. See the snopt documentation for further explanations. More...
 
void getConstraintsMultState (const size_t m, MapVecXs &zMul, MapVecXi &zState) const
 Gets the constraint multiplier and state, used in the NLP solver SNOPT. More...
 
void getBoundMultipliers (size_t n, MapVecXs &zLow, MapVecXs &zUp) const
 Gets the bound multipliers used in the NLP solver IPOPT. More...
 
void getLambdaVars (size_t m, MapVecXs &lambda) const
 Gets the values of the constraint multipliers. More...
 
void extractIpoptSolution (const MapConstVecXs &x, const MapConstVecXs &zL, const MapConstVecXs &zU, const MapConstVecXs &lambda)
 { Extracts the solution values from IPOPT } More...
 
void extractSnoptSolution (const MapVecXs &x, const MapVecXs &xMul, const MapVecXi &xState, const MapVecXs &fMul, const MapVecXi &fState)
 { Extracts the solution values from SNOPT } More...
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef DmsDimensions< STATE_DIM, CONTROL_DIM, SCALARDIMENSIONS
 

Additional Inherited Members

- Protected Attributes inherited from ct::optcon::tpl::Nlp< SCALAR >
std::shared_ptr< DiscreteCostEvaluatorBase< SCALAR > > costEvaluator_
 Ptr to cost evaluator, which approximates the cost evaluation for the discrete problem. More...
 
std::shared_ptr< OptVector< SCALAR > > optVariables_
 Ptr to optimization variable container, which holds the optimization variables used in the NLP solvers. More...
 
std::shared_ptr< DiscreteConstraintContainerBase< SCALAR > > constraints_
 Ptr to constraint container, which contains the discretized constraints for the problem. More...
 
Eigen::VectorXi iRowHessianCost_
 helper containers for calculating the sparsity patterns More...
 
Eigen::VectorXi iRowHessianConstraints_
 
Eigen::VectorXi jColHessianCost_
 
Eigen::VectorXi jColHessianConstraints_
 
Eigen::VectorXi iRowHessian_
 combined Hessian sparsity pattern gets stored here More...
 
Eigen::VectorXi jColHessian_
 

Detailed Description

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

This class sets up the DMS problem.

Member Typedef Documentation

◆ state_vector_t

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
typedef DIMENSIONS::state_vector_t ct::optcon::DmsProblem< 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::DmsProblem< 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::DmsProblem< 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::DmsProblem< 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::DmsProblem< STATE_DIM, CONTROL_DIM, SCALAR >::time_array_t

◆ OptConProblem_t

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

Constructor & Destructor Documentation

◆ DmsProblem()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
ct::optcon::DmsProblem< STATE_DIM, CONTROL_DIM, SCALAR >::DmsProblem ( DmsSettings  settings,
std::vector< typename OptConProblem_t::DynamicsPtr_t systemPtrs,
std::vector< typename OptConProblem_t::LinearPtr_t linearPtrs,
std::vector< typename OptConProblem_t::CostFunctionPtr_t costPtrs,
std::vector< typename OptConProblem_t::ConstraintPtr_t inputBoxConstraints,
std::vector< typename OptConProblem_t::ConstraintPtr_t stateBoxConstraints,
std::vector< typename OptConProblem_t::ConstraintPtr_t generalConstraints,
const state_vector_t x0 
)
inline

Custom constructor, sets up the objects needed for the Dms algorithm depending on the settings.

Parameters
[in]settingsThe Dms settings
[in]systemPtrsThe non linear systems
[in]linearPtrsThe linearized systems
[in]costPtrsThe cost function
[in]inputBoxConstraintsThe input box constraints
[in]stateBoxConstraintsThe state box constraints
[in]generaConstraintsThe general constraints
[in]x0The initial state

References ct::optcon::tpl::Nlp< SCALAR >::constraints_, ct::optcon::DmsSettings::costEvaluationType_, ct::optcon::tpl::Nlp< SCALAR >::costEvaluator_, ct::optcon::DmsSettings::dt_sim_, ct::optcon::DmsSettings::FULL, ct::optcon::tpl::Nlp< SCALAR >::getConstraintsCount(), ct::optcon::DmsSettings::N_, ct::optcon::DmsSettings::objectiveType_, ct::optcon::DmsSettings::OPTIMIZE_GRID, ct::optcon::tpl::Nlp< SCALAR >::optVariables_, ct::optcon::DmsSettings::parametersOk(), ct::optcon::DmsSettings::PIECEWISE_LINEAR, ct::optcon::DmsSettings::SIMPLE, ct::optcon::DmsSettings::splineType_, ct::optcon::DmsSettings::T_, x0, ct::optcon::DmsSettings::ZERO_ORDER_HOLD, and ct::optcon::DmsProblem< STATE_DIM, CONTROL_DIM, SCALAR >::~DmsProblem().

◆ ~DmsProblem()

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

Member Function Documentation

◆ updateProblem()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
void ct::optcon::DmsProblem< STATE_DIM, CONTROL_DIM, SCALAR >::updateProblem ( )
inlineoverridevirtual

{ This method gets called at each update of the Optimization variables. This can be used to distribute or rearrange the optimization variables appropriately }

Implements ct::optcon::tpl::Nlp< SCALAR >.

◆ configure()

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

Updates the settings.

Parameters
[in]settingsNew dms settings

◆ getStateSolution()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
const state_vector_array_t& ct::optcon::DmsProblem< STATE_DIM, CONTROL_DIM, SCALAR >::getStateSolution ( )
inline

Retrieves the solution state trajectory at every shot.

Returns
The state solution trajectory

◆ getInputSolution()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
const control_vector_array_t& ct::optcon::DmsProblem< STATE_DIM, CONTROL_DIM, SCALAR >::getInputSolution ( )
inline

Retrieves the solution control trajectory at every shot.

Returns
The control solution trajectory

◆ getTimeSolution()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
const time_array_t& ct::optcon::DmsProblem< STATE_DIM, CONTROL_DIM, SCALAR >::getTimeSolution ( )
inline

Retrieves the solution time trajectory at every shot.

Returns
The time solution trajectory

◆ getStateTrajectory()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
const state_vector_array_t& ct::optcon::DmsProblem< STATE_DIM, CONTROL_DIM, SCALAR >::getStateTrajectory ( )
inline

Retrieves a dense state solution trajectory.

Returns
The dense state solution trajectory

◆ getInputTrajectory()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
const control_vector_array_t& ct::optcon::DmsProblem< STATE_DIM, CONTROL_DIM, SCALAR >::getInputTrajectory ( )
inline

Retrieves a dense input solution trajectory.

Returns
The dense control solution trajectory

◆ getTimeArray()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
const time_array_t& ct::optcon::DmsProblem< STATE_DIM, CONTROL_DIM, SCALAR >::getTimeArray ( )
inline

Retrieves a dense time solution trajectory.

Returns
The dense time solution trajectory

◆ setInitialGuess()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
void ct::optcon::DmsProblem< STATE_DIM, CONTROL_DIM, SCALAR >::setInitialGuess ( const state_vector_array_t x_init_guess,
const control_vector_array_t u_init_guess,
const time_array_t t_init_guess = time_array_t(0.0) 
)
inline

Sets the initial guess of the optimization.

Parameters
[in]x_init_guessThe state trajectory initial guess
[in]u_init_guessThe control trajectory initial guess
[in]t_init_guessThe time trajectory initial guess

◆ getTimeHorizon()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
const core::Time ct::optcon::DmsProblem< STATE_DIM, CONTROL_DIM, SCALAR >::getTimeHorizon ( ) const
inline

Return the timehorizon of the problem.

Returns
The time horizon

◆ changeTimeHorizon()

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

Updates the timehorizon.

Parameters
[in]tfThe new time horizon

◆ changeInitialState()

template<size_t STATE_DIM, size_t CONTROL_DIM, typename SCALAR = double>
void ct::optcon::DmsProblem< STATE_DIM, CONTROL_DIM, SCALAR >::changeInitialState ( const state_vector_t x0)
inline

Updates the initial state.

Parameters
[in]x0The new inital state

◆ printSolution()

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

Prints the solution trajectories.

Member Data Documentation

◆ DIMENSIONS

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

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