- 3.0.2 optimal control module.
|
#include <NLOptConSolver.hpp>
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_t & | getSolution () override |
virtual const core::StateTrajectory< STATE_DIM, SCALAR > | getStateTrajectory () const override |
virtual const core::ControlTrajectory< CONTROL_DIM, SCALAR > | getControlTrajectory () 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_t & | getSettings () |
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_t > | nlocBackend_ |
the backend holding all the math operations More... | |
std::shared_ptr< NLOCAlgorithm_t > | nlocAlgorithm_ |
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 |
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 |
typedef NLOptConSettings ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::Settings_t |
typedef SCALAR ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::Scalar_t |
typedef Base::OptConProblem_t ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t |
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 |
typedef NLOCAlgorithm_t::Policy_t ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::Policy_t |
typedef NLOCAlgorithm_t::Backend_t ct::optcon::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 >::NLOptConSolver | ( | const OptConProblem_t & | optConProblem, |
const Settings_t & | settings | ||
) |
constructor
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" |
||
) |
|
virtualdefault |
destructor
void ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::initialize | ( | const OptConProblem_t & | optConProblem, |
const Settings_t & | settings | ||
) |
configures the solver
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_, and ct::optcon::NLOptConSettings::nThreads.
|
overridevirtual |
configures the solver
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_, and ct::optcon::NLOptConSettings::nThreads.
Referenced by ct::optcon::example::symplecticTest(), and ct::optcon::example::TEST().
|
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_.
|
virtual |
execute finishing step for an iteration, e.g. solving Riccati backward pass.
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocAlgorithm_.
|
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_.
|
virtual |
execute finishing step for an iteration, e.g. solving Riccati backward pass.
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocAlgorithm_.
|
overridevirtual |
run a single iteration of the solver
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocAlgorithm_.
Referenced by ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::solve(), ct::optcon::example::symplecticTest(), and ct::optcon::example::TEST().
|
override |
Set the initial guess used by the solver (not all solvers might support initial guesses)
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
Referenced by generateSolver(), main(), ct::optcon::example::symplecticTest(), and ct::optcon::example::TEST().
|
overridevirtual |
solve the optimal control problem
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getSettings(), and ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::runIteration().
Referenced by main(), and ct::optcon::example::TEST().
|
overridevirtual |
Get the optimized control policy to the optimal control problem
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
Referenced by main(), and ct::optcon::example::TEST().
|
overridevirtual |
Get the optimized trajectory to the optimal control problem
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
Referenced by ct::optcon::example::symplecticTest(), and ct::optcon::example::TEST().
|
overridevirtual |
Get the optimal feedforward control input corresponding to the optimal trajectory
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
Referenced by ct::optcon::example::symplecticTest(), and ct::optcon::example::TEST().
|
overridevirtual |
Get the time indices corresponding to the solution
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
|
overridevirtual |
Get the time horizon the solver currently operates on.
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
|
overridevirtual |
Change the time horizon the solver operates on.
This function does not need to be called if setOptConProblem() has been called with an OptConProblem that had the correct time horizon set.
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
|
overridevirtual |
Change the initial state for the optimal control problem.
This function does not need to be called if setOptConProblem() has been called with an OptConProblem that had the correct initial state set
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
|
overridevirtual |
Change the cost function.
This function does not need to be called if setOptConProblem() has been called with an OptConProblem that had the correct cost function
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
|
overridevirtual |
Change the nonlinear system.
This function does not need to be called if setOptConProblem() has been called with an OptConProblem that had the correct nonlinear system
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
|
overridevirtual |
Change the linear system.
This function does not need to be called if setOptConProblem() has been called with an OptConProblem that had the correct linear system
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
|
overridevirtual |
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 | ( | ) |
get a reference to the current settings
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
Referenced by ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::solve().
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 (
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
Referenced by ct::optcon::example::TEST().
|
overridevirtual |
get reference to the nonlinear system
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
|
overridevirtual |
get constant reference to the nonlinear system
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
|
overridevirtual |
get reference to the linearized system
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
|
overridevirtual |
get constant reference to the linearized system
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
|
overridevirtual |
get reference to the cost function
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
|
overridevirtual |
get constant reference to the cost function
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
|
overridevirtual |
get reference to the box constraints
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
|
overridevirtual |
get constant reference to the boxconstraints
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
|
overridevirtual |
get reference to the box constraints
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
|
overridevirtual |
get constant reference to the boxconstraints
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
|
overridevirtual |
get reference to the general constraints
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
|
overridevirtual |
get constant reference to the general constraints
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
void ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::logSummaryToMatlab | ( | const std::string & | fileName | ) |
logging a short summary to matlab
References ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nlocBackend_.
|
static |
|
static |
|
static |
|
static |
|
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().
|
protected |
the algorithm for sequencing the math operations in correct manner
Referenced by ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::finishIteration(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::finishMPCIteration(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::NLOptConSolver(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::prepareIteration(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::prepareMPCIteration(), and ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::runIteration().