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

C++ implementation of GNMS. More...

#include <NLOCBackendBase.hpp>

Inheritance diagram for ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >:
ct::optcon::NLOCBackendMP< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS > ct::optcon::NLOCBackendST< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >

Public Types

typedef NLOptConSettings Settings_t
 
typedef ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALARPolicy_t
 
typedef std::conditional< CONTINUOUS, ContinuousOptConProblem< STATE_DIM, CONTROL_DIM, SCALAR >, DiscreteOptConProblem< STATE_DIM, CONTROL_DIM, SCALAR > >::type OptConProblem_t
 
typedef LQOCProblem< STATE_DIM, CONTROL_DIM, SCALARLQOCProblem_t
 
typedef LQOCSolver< STATE_DIM, CONTROL_DIM, SCALARLQOCSolver_t
 
typedef ct::core::StateVectorArray< STATE_DIM, SCALARStateVectorArray
 
typedef std::shared_ptr< StateVectorArrayStateVectorArrayPtr
 
typedef ct::core::ControlVectorArray< CONTROL_DIM, SCALARControlVectorArray
 
typedef std::shared_ptr< ControlVectorArrayControlVectorArrayPtr
 
typedef std::vector< StateVectorArrayPtr, Eigen::aligned_allocator< StateVectorArrayPtr > > StateSubsteps
 
typedef std::shared_ptr< StateSubstepsStateSubstepsPtr
 
typedef std::vector< ControlVectorArrayPtr, Eigen::aligned_allocator< ControlVectorArrayPtr > > ControlSubsteps
 
typedef std::shared_ptr< ControlSubstepsControlSubstepsPtr
 
typedef OptconSystemInterface< STATE_DIM, CONTROL_DIM, OptConProblem_t, SCALARsystemInterface_t
 
typedef std::shared_ptr< systemInterface_tsystemInterfacePtr_t
 
using ControlMatrix = ct::core::ControlMatrix< CONTROL_DIM, SCALAR >
 
using ControlMatrixArray = ct::core::ControlMatrixArray< CONTROL_DIM, SCALAR >
 
using StateMatrixArray = ct::core::StateMatrixArray< STATE_DIM, SCALAR >
 
using StateControlMatrixArray = ct::core::StateControlMatrixArray< STATE_DIM, CONTROL_DIM, SCALAR >
 
using FeedbackArray = ct::core::FeedbackArray< STATE_DIM, CONTROL_DIM, SCALAR >
 
using TimeArray = ct::core::tpl::TimeArray< SCALAR >
 
using state_matrix_t = Eigen::Matrix< SCALAR, STATE_DIM, STATE_DIM >
 
using control_matrix_t = Eigen::Matrix< SCALAR, CONTROL_DIM, CONTROL_DIM >
 
using control_state_matrix_t = Eigen::Matrix< SCALAR, CONTROL_DIM, STATE_DIM >
 
using state_control_matrix_t = Eigen::Matrix< SCALAR, STATE_DIM, CONTROL_DIM >
 
using state_vector_t = core::StateVector< STATE_DIM, SCALAR >
 
using control_vector_t = core::ControlVector< CONTROL_DIM, SCALAR >
 
using feedback_matrix_t = core::FeedbackMatrix< STATE_DIM, CONTROL_DIM, SCALAR >
 
using scalar_t = SCALAR
 
using scalar_array_t = std::vector< SCALAR, Eigen::aligned_allocator< SCALAR > >
 

Public Member Functions

 NLOCBackendBase (const OptConProblem_t &optConProblem, const Settings_t &settings)
 
 NLOCBackendBase (const OptConProblem_t &optConProblem, const std::string &settingsFile, bool verbose=true, const std::string &ns="alg")
 
 NLOCBackendBase (const systemInterfacePtr_t &systemInterface, const Settings_t &settings)
 
 NLOCBackendBase (const systemInterfacePtr_t &systemInterface, const std::string &settingsFile, bool verbose=true, const std::string &ns="alg")
 
virtual ~NLOCBackendBase ()
 
template<typename T = OptConProblem_t>
std::enable_if< std::is_same< T, ContinuousOptConProblem< STATE_DIM, CONTROL_DIM, SCALAR > >::value, systemInterfacePtr_t >::type createSystemInterface (const OptConProblem_t &optConProblem, const Settings_t &settings)
 
template<typename T = OptConProblem_t>
std::enable_if< std::is_same< T, DiscreteOptConProblem< STATE_DIM, CONTROL_DIM, SCALAR > >::value, systemInterfacePtr_t >::type createSystemInterface (const OptConProblem_t &optConProblem, const Settings_t &settings)
 
virtual void configure (const Settings_t &settings)
 configure the solver More...
 
const Settings_tgetSettings () const
 get the current SLQsolver settings More...
 
void setInitialGuess (const Policy_t &initialGuess)
 
void changeTimeHorizon (const SCALAR &tf)
 Change the time horizon the solver operates on. More...
 
void changeTimeHorizon (int numStages)
 
SCALAR getTimeHorizon ()
 
int getNumSteps ()
 
int getNumStepsPerShot () const
 
void changeInitialState (const core::StateVector< STATE_DIM, SCALAR > &x0)
 Change the initial state for the optimal control problem. More...
 
void changeCostFunction (const typename OptConProblem_t::CostFunctionPtr_t &cf)
 Change the cost function. More...
 
void changeNonlinearSystem (const typename OptConProblem_t::DynamicsPtr_t &dyn)
 Change the nonlinear system. More...
 
void changeLinearSystem (const typename OptConProblem_t::LinearPtr_t &lin)
 Change the linear system. More...
 
void changeInputBoxConstraints (const typename OptConProblem_t::ConstraintPtr_t &con)
 Change the input box constraints. More...
 
void changeStateBoxConstraints (const typename OptConProblem_t::ConstraintPtr_t &con)
 Change the state box constraints. More...
 
void changeGeneralConstraints (const typename OptConProblem_t::ConstraintPtr_t &con)
 Change the general constraints. More...
 
std::vector< typename OptConProblem_t::DynamicsPtr_t > & getNonlinearSystemsInstances ()
 Direct accessor to the system instances. More...
 
const std::vector< typename OptConProblem_t::DynamicsPtr_t > & getNonlinearSystemsInstances () const
 
std::vector< typename OptConProblem_t::LinearPtr_t > & getLinearSystemsInstances ()
 Direct accessor to the linear system instances. More...
 
const std::vector< typename OptConProblem_t::LinearPtr_t > & getLinearSystemsInstances () const
 
std::vector< typename OptConProblem_t::CostFunctionPtr_t > & getCostFunctionInstances ()
 Direct accessor to the cost function instances. More...
 
const std::vector< typename OptConProblem_t::CostFunctionPtr_t > & getCostFunctionInstances () const
 
std::vector< typename OptConProblem_t::ConstraintPtr_t > & getInputBoxConstraintsInstances ()
 Direct accessor to the box constraint instances. More...
 
std::vector< typename OptConProblem_t::ConstraintPtr_t > & getStateBoxConstraintsInstances ()
 
const std::vector< typename OptConProblem_t::ConstraintPtr_t > & getInputBoxConstraintsInstances () const
 
const std::vector< typename OptConProblem_t::ConstraintPtr_t > & getStateBoxConstraintsInstances () const
 
std::vector< typename OptConProblem_t::ConstraintPtr_t > & getGeneralConstraintsInstances ()
 Direct accessor to the general constraints. More...
 
const std::vector< typename OptConProblem_t::ConstraintPtr_t > & getGeneralConstraintsInstances () const
 
bool testConsistency ()
 
void logToMatlab (const size_t &iteration)
 Export all functions to matlab workspace. More...
 
void logInitToMatlab ()
 log the initial guess to Matlab More...
 
SCALAR getCost () const
 return the cost of the solution of the current iteration More...
 
SCALAR getTotalDefect () const
 return the sum of the L2-norm of the defects along the solution candidate More...
 
void reset ()
 
const core::StateTrajectory< STATE_DIM, SCALARgetStateTrajectory () const
 
const core::ControlTrajectory< CONTROL_DIM, SCALARgetControlTrajectory () const
 
const Policy_tgetSolution ()
 
const TimeArraygetTimeArray ()
 
bool isConfigured ()
 
bool isInitialized ()
 
void retrieveLastAffineModel (StateMatrixArray &A, StateControlMatrixArray &B, StateVectorArray &b)
 Retrieve Last Linearized Model. More...
 
virtual void prepareSolveLQProblem (size_t startIndex)
 
virtual void finishSolveLQProblem (size_t endIndex)
 
virtual void solveFullLQProblem ()
 
void extractSolution ()
 extract relevant quantities for the following rollout/solution update step from the LQ solver More...
 
void updateCosts ()
 compute costs of solution candidate More...
 
bool nominalRollout ()
 nominal rollout using default thread and member variables for the results. // todo maybe rename (initial rollout?) More...
 
void checkProblem ()
 check problem for consistency More...
 
size_t & iteration ()
 return the current iteration number More...
 
void printSummary ()
 Print iteration summary. More...
 
bool lineSearch ()
 perform line-search and update controller More...
 
virtual void computeLQApproximation (size_t firstIndex, size_t lastIndex)=0
 build LQ approximation around trajectory (linearize dynamics and general constraints, quadratize cost, etc) More...
 
void setInputBoxConstraintsForLQOCProblem ()
 sets the box constraints for the entire time horizon including terminal stage More...
 
void setStateBoxConstraintsForLQOCProblem ()
 
void resetDefects ()
 reset all defects to zero More...
 
void computeDefectsNorm ()
 update the nominal defects More...
 
virtual void rolloutShots (size_t firstIndex, size_t lastIndex)=0
 integrates the specified shots and computes the corresponding defects More...
 
bool rolloutShotsSingleThreaded (size_t threadId, size_t firstIndex, size_t lastIndex, ControlVectorArray &u_ff_local, StateVectorArray &x_local, const StateVectorArray &x_ref_lqr, StateVectorArray &xShot, StateVectorArray &d, StateSubsteps &substepsX, ControlSubsteps &substepsU, std::atomic_bool *terminationFlag=nullptr) const
 do a single threaded rollout and defect computation of the shots - useful for line-search More...
 
virtual SCALAR performLineSearch ()=0
 performLineSearch: execute the line search, possibly with different threading schemes More...
 
void doFullStepUpdate ()
 simple full-step update for state and feedforward control (used for MPC-mode!) More...
 
void logSummaryToMatlab (const std::string &fileName)
 
const SummaryAllIterations< SCALAR > & getSummary () const
 

Static Public Attributes

static EIGEN_MAKE_ALIGNED_OPERATOR_NEW const size_t state_dim = STATE_DIM
 
static const size_t control_dim = CONTROL_DIM
 

Protected Member Functions

bool rolloutSingleShot (const size_t threadId, const size_t k, ControlVectorArray &u_ff_local, StateVectorArray &x_local, const StateVectorArray &x_ref_lqr, StateVectorArray &xShot, StateSubsteps &substepsX, ControlSubsteps &substepsU, std::atomic_bool *terminationFlag=nullptr) const
 integrate the individual shots More...
 
void computeSingleDefect (size_t k, const StateVectorArray &x_local, const StateVectorArray &xShot, StateVectorArray &d) const
 computes the defect between shot and trajectory More...
 
void executeLQApproximation (size_t threadId, size_t k)
 Computes the linearized Dynamics and quadratic cost approximation at a specific point of the trajectory. More...
 
void computeLinearizedConstraints (size_t threadId, size_t k)
 Computes the linearized general constraints at a specific point of the trajectory. More...
 
void initializeCostToGo ()
 Initializes cost to go. More...
 
void computeCostToGo (size_t k)
 Computes cost to go. More...
 
void designController (size_t k)
 Design controller. More...
 
void computeCostsOfTrajectory (size_t threadId, const core::StateVectorArray< STATE_DIM, SCALAR > &x_local, const core::ControlVectorArray< CONTROL_DIM, SCALAR > &u_local, scalar_t &intermediateCost, scalar_t &finalCost) const
 Compute cost for a given set of state and input trajectory. More...
 
void computeBoxConstraintErrorOfTrajectory (size_t threadId, const ct::core::StateVectorArray< STATE_DIM, SCALAR > &x_local, const ct::core::ControlVectorArray< CONTROL_DIM, SCALAR > &u_local, scalar_t &e_tot) const
 Compute box constraint violations for a given set of state and input trajectory. More...
 
void computeGeneralConstraintErrorOfTrajectory (size_t threadId, const ct::core::StateVectorArray< STATE_DIM, SCALAR > &x_local, const ct::core::ControlVectorArray< CONTROL_DIM, SCALAR > &u_local, scalar_t &e_tot) const
 Compute general constraint violations for a given set of state and input trajectory. More...
 
void executeLineSearch (const size_t threadId, const scalar_t alpha, ct::core::StateVectorArray< STATE_DIM, SCALAR > &x_recorded, ct::core::StateVectorArray< STATE_DIM, SCALAR > &x_shot_recorded, ct::core::StateVectorArray< STATE_DIM, SCALAR > &defects_recorded, ct::core::ControlVectorArray< CONTROL_DIM, SCALAR > &u_recorded, scalar_t &intermediateCost, scalar_t &finalCost, scalar_t &defectNorm, scalar_t &e_box_norm, scalar_t &e_gen_norm, StateSubsteps &substepsX, ControlSubsteps &substepsU, std::atomic_bool *terminationFlag=nullptr) const
 Check if controller with particular alpha is better. More...
 
bool acceptStep (const SCALAR alpha, const SCALAR intermediateCost, const SCALAR finalCost, const SCALAR defectNorm, const SCALAR e_box_norm, const SCALAR e_gen_norm, const SCALAR lowestMeritPrevious, SCALAR &new_merit)
 in case of line-search compute new merit and check if to accept step. Returns true if accept step More...
 
void updateFFController (size_t k)
 Update feedforward controller. More...
 
template<typename ARRAY_TYPE , size_t ORDER = 1>
SCALAR computeDiscreteArrayNorm (const ARRAY_TYPE &d) const
 compute norm of a discrete array (todo move to core) More...
 
template<typename ARRAY_TYPE , size_t ORDER = 1>
SCALAR computeDiscreteArrayNorm (const ARRAY_TYPE &a, const ARRAY_TYPE &b) const
 compute norm of difference between two discrete arrays (todo move to core) More...
 
template<size_t ORDER = 1>
SCALAR computeDefectsNorm (const StateVectorArray &d) const
 compute the norm of the defects trajectory More...
 

Protected Attributes

bool initialized_
 
bool configured_
 
size_t iteration_
 
bool firstRollout_
 
Settings_t settings_
 
int K_
 
ct::core::tpl::TimeArray< SCALARt_
 the number of stages in the overall OptConProblem More...
 
StateVectorArray x_
 the time trajectory More...
 
StateVectorArray xShot_
 state array variables More...
 
StateVectorArray d_
 rolled-out state (at the end of a time step forward) More...
 
StateVectorArray x_prev_
 defects in between end of rollouts and subsequent state decision vars More...
 
StateVectorArray x_ref_lqr_
 state array from previous iteration More...
 
ControlVectorArray u_ff_
 reference for lqr More...
 
ControlVectorArray u_ff_prev_
 feed forward controls More...
 
FeedbackArray L_
 feed forward controls from previous iteration More...
 
ControlVectorArray delta_u_ff_
 time-varying lqr feedback More...
 
StateVectorArray delta_x_
 pointer to control increment More...
 
StateVectorArray delta_x_ref_lqr_
 pointer to state increment More...
 
StateSubstepsPtr substepsX_
 state array from previous iteration More...
 
ControlSubstepsPtr substepsU_
 state substeps recorded by integrator during rollouts More...
 
SCALAR d_norm_
 control substeps recorded by integrator during rollouts More...
 
SCALAR e_box_norm_
 sum of the norms of all defects (internal constraint) More...
 
SCALAR e_gen_norm_
 sum of the norms of all box constraint violations More...
 
SCALAR lx_norm_
 sum of the norms of all general constraint violations More...
 
SCALAR lu_norm_
 sum of the norms of state update More...
 
scalar_t intermediateCostBest_
 sum of the norms of control update More...
 
scalar_t finalCostBest_
 
scalar_t lowestCost_
 
scalar_t intermediateCostPrevious_
 costs of the previous iteration, required to determine convergence More...
 
scalar_t finalCostPrevious_
 
scalar_t alphaBest_
 
std::shared_ptr< LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR > > lqocProblem_
 shared pointer to the linear-quadratic optimal control problem that is constructed by NLOC More...
 
std::shared_ptr< LQOCSolver< STATE_DIM, CONTROL_DIM, SCALAR > > lqocSolver_
 shared pointer to the linear-quadratic optimal control solver, that solves above LQOCP More...
 
systemInterfacePtr_t systemInterface_
 pointer to instance of the system interface More...
 
std::vector< typename OptConProblem_t::CostFunctionPtr_t > costFunctions_
 
std::vector< typename OptConProblem_t::ConstraintPtr_t > inputBoxConstraints_
 
std::vector< typename OptConProblem_t::ConstraintPtr_t > stateBoxConstraints_
 
std::vector< typename OptConProblem_t::ConstraintPtr_t > generalConstraints_
 
size_t lqpCounter_
 a counter used to identify lqp problems in derived classes, i.e. for thread management in MP More...
 
NLOCBackendBase::Policy_t policy_
 The policy. currently only for returning the result, should eventually replace L_ and u_ff_ (todo) More...
 
SummaryAllIterations< SCALARsummaryAllIterations_
 

Detailed Description

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

C++ implementation of GNMS.

The implementation and naming is based on the reference below. In general, the code follows this convention: X <- Matrix (upper-case in paper) xv <- vector (lower-case bold in paper) x <- scalar (lower-case in paper)

Member Typedef Documentation

◆ Settings_t

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

◆ Policy_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
typedef ct::core::StateFeedbackController<STATE_DIM, CONTROL_DIM, SCALAR> ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::Policy_t

◆ OptConProblem_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
typedef std::conditional<CONTINUOUS, ContinuousOptConProblem<STATE_DIM, CONTROL_DIM, SCALAR>, DiscreteOptConProblem<STATE_DIM, CONTROL_DIM, SCALAR> >::type ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t

◆ LQOCProblem_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
typedef LQOCProblem<STATE_DIM, CONTROL_DIM, SCALAR> ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::LQOCProblem_t

◆ LQOCSolver_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
typedef LQOCSolver<STATE_DIM, CONTROL_DIM, SCALAR> ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::LQOCSolver_t

◆ StateVectorArray

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
typedef ct::core::StateVectorArray<STATE_DIM, SCALAR> ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::StateVectorArray

◆ StateVectorArrayPtr

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
typedef std::shared_ptr<StateVectorArray> ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::StateVectorArrayPtr

◆ ControlVectorArray

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
typedef ct::core::ControlVectorArray<CONTROL_DIM, SCALAR> ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::ControlVectorArray

◆ ControlVectorArrayPtr

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
typedef std::shared_ptr<ControlVectorArray> ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::ControlVectorArrayPtr

◆ StateSubsteps

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
typedef std::vector<StateVectorArrayPtr, Eigen::aligned_allocator<StateVectorArrayPtr> > ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::StateSubsteps

◆ StateSubstepsPtr

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
typedef std::shared_ptr<StateSubsteps> ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::StateSubstepsPtr

◆ ControlSubsteps

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
typedef std::vector<ControlVectorArrayPtr, Eigen::aligned_allocator<ControlVectorArrayPtr> > ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::ControlSubsteps

◆ ControlSubstepsPtr

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
typedef std::shared_ptr<ControlSubsteps> ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::ControlSubstepsPtr

◆ systemInterface_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
typedef OptconSystemInterface<STATE_DIM, CONTROL_DIM, OptConProblem_t, SCALAR> ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::systemInterface_t

◆ systemInterfacePtr_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
typedef std::shared_ptr<systemInterface_t> ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::systemInterfacePtr_t

◆ ControlMatrix

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::ControlMatrix = ct::core::ControlMatrix<CONTROL_DIM, SCALAR>

◆ ControlMatrixArray

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::ControlMatrixArray = ct::core::ControlMatrixArray<CONTROL_DIM, SCALAR>

◆ StateMatrixArray

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::StateMatrixArray = ct::core::StateMatrixArray<STATE_DIM, SCALAR>

◆ StateControlMatrixArray

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::StateControlMatrixArray = ct::core::StateControlMatrixArray<STATE_DIM, CONTROL_DIM, SCALAR>

◆ FeedbackArray

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::FeedbackArray = ct::core::FeedbackArray<STATE_DIM, CONTROL_DIM, SCALAR>

◆ TimeArray

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::TimeArray = ct::core::tpl::TimeArray<SCALAR>

◆ state_matrix_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::state_matrix_t = Eigen::Matrix<SCALAR, STATE_DIM, STATE_DIM>

◆ control_matrix_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::control_matrix_t = Eigen::Matrix<SCALAR, CONTROL_DIM, CONTROL_DIM>

◆ control_state_matrix_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::control_state_matrix_t = Eigen::Matrix<SCALAR, CONTROL_DIM, STATE_DIM>

◆ state_control_matrix_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::state_control_matrix_t = Eigen::Matrix<SCALAR, STATE_DIM, CONTROL_DIM>

◆ state_vector_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::state_vector_t = core::StateVector<STATE_DIM, SCALAR>

◆ control_vector_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::control_vector_t = core::ControlVector<CONTROL_DIM, SCALAR>

◆ feedback_matrix_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::feedback_matrix_t = core::FeedbackMatrix<STATE_DIM, CONTROL_DIM, SCALAR>

◆ scalar_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::scalar_t = SCALAR

◆ scalar_array_t

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::scalar_array_t = std::vector<SCALAR, Eigen::aligned_allocator<SCALAR> >

Constructor & Destructor Documentation

◆ NLOCBackendBase() [1/4]

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

◆ NLOCBackendBase() [2/4]

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

◆ NLOCBackendBase() [3/4]

◆ NLOCBackendBase() [4/4]

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

◆ ~NLOCBackendBase()

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

Member Function Documentation

◆ createSystemInterface() [1/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
template<typename T >
std::enable_if< std::is_same< T, DiscreteOptConProblem< STATE_DIM, CONTROL_DIM, SCALAR > >::value, typename NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::systemInterfacePtr_t >::type ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::createSystemInterface ( const OptConProblem_t optConProblem,
const Settings_t settings 
)

◆ createSystemInterface() [2/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
template<typename T = OptConProblem_t>
std::enable_if<std::is_same<T, DiscreteOptConProblem<STATE_DIM, CONTROL_DIM, SCALAR> >::value, systemInterfacePtr_t>::type ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::createSystemInterface ( const OptConProblem_t optConProblem,
const Settings_t settings 
)

◆ configure()

◆ getSettings()

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

◆ 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::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::setInitialGuess ( const Policy_t initialGuess)

Set the initial guess used by the solver (not all solvers might support initial guesses)

References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeCostsOfTrajectory(), ct::optcon::NLOptConSettings::dt, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::finalCostBest_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::finalCostPrevious_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::initialized_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::intermediateCostBest_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::intermediateCostPrevious_, ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::K(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::K_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::L_, ct::optcon::NLOptConSettings::nThreads, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::reset(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::settings_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::t_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::u_ff_, ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::uff(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::x_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::x_prev_, ct::core::StateFeedbackController< STATE_DIM, CONTROL_DIM, SCALAR >::x_ref(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::x_ref_lqr_.

◆ changeTimeHorizon() [1/2]

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

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::NLOptConSettings::computeK(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::settings_.

Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::NLOCBackendBase().

◆ changeTimeHorizon() [2/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeTimeHorizon ( int  numStages)

References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::d_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::delta_u_ff_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::delta_x_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::delta_x_ref_lqr_, ct::optcon::NLOptConSettings::dt, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::K_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::L_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lqocProblem_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lqocSolver_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::resetDefects(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::settings_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::substepsU_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::substepsX_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::systemInterface_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::t_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::u_ff_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::u_ff_prev_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::x_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::x_prev_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::x_ref_lqr_, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::xShot_.

◆ 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::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getTimeHorizon ( )

◆ getNumSteps()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
int ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getNumSteps ( )

◆ getNumStepsPerShot()

◆ 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::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeInitialState ( const core::StateVector< STATE_DIM, SCALAR > &  x0)

◆ changeCostFunction()

◆ 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::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeNonlinearSystem ( const typename OptConProblem_t::DynamicsPtr_t &  dyn)

◆ 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::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeLinearSystem ( const typename OptConProblem_t::LinearPtr_t &  lin)

◆ changeInputBoxConstraints()

◆ changeStateBoxConstraints()

◆ changeGeneralConstraints()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeGeneralConstraints ( const typename OptConProblem_t::ConstraintPtr_t &  con)

◆ 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 NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t::DynamicsPtr_t > & ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getNonlinearSystemsInstances ( )

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

References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::systemInterface_.

◆ 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 NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t::DynamicsPtr_t > & ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getNonlinearSystemsInstances ( ) const

◆ 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 NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t::LinearPtr_t > & ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getLinearSystemsInstances ( )

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

References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::systemInterface_.

◆ 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 NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t::LinearPtr_t > & ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getLinearSystemsInstances ( ) const

◆ 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 NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t::CostFunctionPtr_t > & ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getCostFunctionInstances ( )

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

References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::costFunctions_.

◆ 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 NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t::CostFunctionPtr_t > & ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getCostFunctionInstances ( ) const

◆ 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 NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t::ConstraintPtr_t > & ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getInputBoxConstraintsInstances ( )

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 box constraint instances

References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::inputBoxConstraints_.

◆ 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 NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t::ConstraintPtr_t > & ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getStateBoxConstraintsInstances ( )

◆ 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 NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t::ConstraintPtr_t > & ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getInputBoxConstraintsInstances ( ) const

◆ 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 NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t::ConstraintPtr_t > & ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getStateBoxConstraintsInstances ( ) const

◆ 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 NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t::ConstraintPtr_t > & ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getGeneralConstraintsInstances ( )

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.

References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::generalConstraints_.

◆ 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 NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t::ConstraintPtr_t > & ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getGeneralConstraintsInstances ( ) const

◆ testConsistency()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
bool ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::testConsistency ( )

Tests consistency of the instance of the dynamics, linear systems and costs. This is not a test for thread safety.

Returns
returns true if instances are consistent with each other

◆ logToMatlab()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::logToMatlab ( const size_t &  iteration)

Export all functions to matlab workspace.

This function can be used for Debugging. It exports all variables to Matlab after each iteration. It also saves the Matlab workspace to a .mat file.

References ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::A_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::alphaBest_, ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::B_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeBoxConstraintErrorOfTrajectory(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeGeneralConstraintErrorOfTrajectory(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::d_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::d_norm_, ct::optcon::NLOptConSettings::dt, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::e_box_norm_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::e_gen_norm_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getCost(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::K_, ct::optcon::NLOptConSettings::K_sim, ct::optcon::NLOptConSettings::loggingPrefix, ct::optcon::NLOptConSettings::logToMatlab, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lqocProblem_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lu_norm_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lx_norm_, ct::optcon::NLOptConSettings::nThreads, ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::P_, ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::q_, ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::Q_, ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::qv_, ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::R_, ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::rv_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::settings_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::t_, ct::core::DiscreteArray< T, Alloc >::toImplementation(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::u_ff_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::x_, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::xShot_.

◆ logInitToMatlab()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::logInitToMatlab ( )

◆ getCost()

◆ getTotalDefect()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
SCALAR ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getTotalDefect ( ) const

return the sum of the L2-norm of the defects along the solution candidate

References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::d_norm_.

◆ reset()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::reset ( )

◆ 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::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getStateTrajectory ( ) const

◆ 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::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getControlTrajectory ( ) const

◆ getSolution()

◆ getTimeArray()

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

◆ isConfigured()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
bool ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::isConfigured ( )

◆ isInitialized()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
bool ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::isInitialized ( )

◆ retrieveLastAffineModel()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::retrieveLastAffineModel ( StateMatrixArray A,
StateControlMatrixArray B,
StateVectorArray b 
)

Retrieve Last Linearized Model.

Retrieve the linearized model computed during the last iteration

References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lqocProblem_.

◆ prepareSolveLQProblem()

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

◆ finishSolveLQProblem()

◆ solveFullLQProblem()

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

◆ extractSolution()

◆ updateCosts()

◆ nominalRollout()

◆ checkProblem()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::checkProblem ( )

◆ iteration()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
size_t & ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::iteration ( )

◆ printSummary()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::printSummary ( )

Print iteration summary.

This function is automatically called if the printSummary settings is on. It prints out important information like cost etc. after each iteration.

Todo:
the printing of the smallest eigenvalue is hacky

References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::alphaBest_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeBoxConstraintErrorOfTrajectory(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeGeneralConstraintErrorOfTrajectory(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::d_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::e_box_norm_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::e_gen_norm_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::finalCostBest_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::intermediateCostBest_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::iteration_, ct::optcon::NLOptConSettings::lqocp_solver, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lqocSolver_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lu_norm_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lx_norm_, ct::optcon::NLOptConSettings::meritFunctionRho, ct::optcon::NLOptConSettings::meritFunctionRhoConstraints, ct::optcon::NLOptConSettings::nThreads, ct::optcon::NLOptConSettings::printSummary, ct::optcon::NLOptConSettings::recordSmallestEigenvalue, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::settings_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::summaryAllIterations_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::u_ff_, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::x_.

◆ lineSearch()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
bool ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lineSearch ( )

perform line-search and update controller

found better cost

References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::alphaBest_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::d_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::d_norm_, ct::optcon::LineSearchSettings::debugPrint, ct::optcon::NLOptConSettings::debugPrint, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::doFullStepUpdate(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::e_box_norm_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::e_gen_norm_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::finalCostBest_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::intermediateCostBest_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::K_, ct::optcon::NLOptConSettings::lineSearchSettings, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lowestCost_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lu_norm_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lx_norm_, ct::optcon::NLOptConSettings::maxDefectSum, ct::optcon::NLOptConSettings::meritFunctionRho, ct::optcon::NLOptConSettings::meritFunctionRhoConstraints, ct::optcon::NLOptConSettings::min_cost_improvement, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::performLineSearch(), ct::optcon::NLOptConSettings::printSummary, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::resetDefects(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutShots(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::settings_, ct::optcon::LineSearchSettings::type, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::u_ff_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::u_ff_prev_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::updateCosts(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::x_, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::x_prev_.

◆ computeLQApproximation()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
virtual void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeLQApproximation ( size_t  firstIndex,
size_t  lastIndex 
)
pure virtual

build LQ approximation around trajectory (linearize dynamics and general constraints, quadratize cost, etc)

Implemented in ct::optcon::NLOCBackendMP< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >, and ct::optcon::NLOCBackendST< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >.

◆ setInputBoxConstraintsForLQOCProblem()

◆ setStateBoxConstraintsForLQOCProblem()

◆ resetDefects()

◆ computeDefectsNorm() [1/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeDefectsNorm ( )

◆ rolloutShots()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
virtual void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutShots ( size_t  firstIndex,
size_t  lastIndex 
)
pure virtual

◆ rolloutShotsSingleThreaded()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
bool ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutShotsSingleThreaded ( size_t  threadId,
size_t  firstIndex,
size_t  lastIndex,
ControlVectorArray u_ff_local,
StateVectorArray x_local,
const StateVectorArray x_ref_lqr,
StateVectorArray xShot,
StateVectorArray d,
StateSubsteps substepsX,
ControlSubsteps substepsU,
std::atomic_bool *  terminationFlag = nullptr 
) const

◆ performLineSearch()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
virtual SCALAR ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::performLineSearch ( )
pure virtual

◆ doFullStepUpdate()

◆ 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::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::logSummaryToMatlab ( const std::string &  fileName)

◆ getSummary()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
const SummaryAllIterations< SCALAR > & ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getSummary ( ) const

◆ rolloutSingleShot()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
bool ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutSingleShot ( const size_t  threadId,
const size_t  k,
ControlVectorArray u_local,
StateVectorArray x_local,
const StateVectorArray x_ref_lqr,
StateVectorArray xShot,
StateSubsteps substepsX,
ControlSubsteps substepsU,
std::atomic_bool *  terminationFlag = nullptr 
) const
protected

◆ computeSingleDefect()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeSingleDefect ( size_t  k,
const StateVectorArray x_local,
const StateVectorArray xShot,
StateVectorArray d 
) const
protected

◆ executeLQApproximation()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::executeLQApproximation ( size_t  threadId,
size_t  k 
)
protected

Computes the linearized Dynamics and quadratic cost approximation at a specific point of the trajectory.

This function calculates the affine dynamics approximation, i.e. matrices A, B and b in $ \delta x_{n+1} = A_n \delta x_n + B_n \delta u_n + b_n $ at a specific point of the trajectory. This function also calculates the quadratic costs as provided by the costFunction pointer. and maps it into the coordinates of the LQ problem.

Parameters
threadIdthe id of the worker thread
kstep k
Warning
it is important that the calculations are done with local variables x_ and u_ff_, they will only later be stored in the LQOCProblem

References ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::A_, ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::B_, ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::b_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::costFunctions_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::d_, dt, ct::optcon::NLOptConSettings::dt, ct::optcon::NLOptConSettings::K_sim, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lqocProblem_, ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::P_, ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::Q_, ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::qv_, ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::R_, ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::rv_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::settings_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::substepsU_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::substepsX_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::systemInterface_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::u_ff_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::x_, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::xShot_.

Referenced by ct::optcon::NLOCBackendST< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeLQApproximation(), and ct::optcon::NLOCBackendMP< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeLQApproximation().

◆ computeLinearizedConstraints()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeLinearizedConstraints ( size_t  threadId,
size_t  k 
)
protected

◆ initializeCostToGo()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::initializeCostToGo ( )
protected

◆ computeCostToGo()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeCostToGo ( size_t  k)
protected

Computes cost to go.

This function computes the cost-to-go function for all times t<t_K

Parameters
kstep k

◆ designController()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::designController ( size_t  k)
protected

Design controller.

This function designes the LQR and feedforward controller at time k.

Parameters
kstep k

◆ computeCostsOfTrajectory()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeCostsOfTrajectory ( size_t  threadId,
const core::StateVectorArray< STATE_DIM, SCALAR > &  x_local,
const core::ControlVectorArray< CONTROL_DIM, SCALAR > &  u_local,
scalar_t intermediateCost,
scalar_t finalCost 
) const
protected

◆ computeBoxConstraintErrorOfTrajectory()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeBoxConstraintErrorOfTrajectory ( size_t  threadId,
const ct::core::StateVectorArray< STATE_DIM, SCALAR > &  x_local,
const ct::core::ControlVectorArray< CONTROL_DIM, SCALAR > &  u_local,
scalar_t e_tot 
) const
protected

Compute box constraint violations for a given set of state and input trajectory.

Parameters
threadIdthe ID of the thread
x_localthe state trajectory
u_localthe control trajectory
e_totthe total accumulated box constraint violation

References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeGeneralConstraintErrorOfTrajectory(), ct::optcon::NLOptConSettings::dt, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::inputBoxConstraints_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::K_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::settings_, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::stateBoxConstraints_.

Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeInputBoxConstraints(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeStateBoxConstraints(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::executeLineSearch(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::logInitToMatlab(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::logToMatlab(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::printSummary().

◆ computeGeneralConstraintErrorOfTrajectory()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeGeneralConstraintErrorOfTrajectory ( size_t  threadId,
const ct::core::StateVectorArray< STATE_DIM, SCALAR > &  x_local,
const ct::core::ControlVectorArray< CONTROL_DIM, SCALAR > &  u_local,
scalar_t e_tot 
) const
protected

◆ executeLineSearch()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::executeLineSearch ( const size_t  threadId,
const scalar_t  alpha,
ct::core::StateVectorArray< STATE_DIM, SCALAR > &  x_recorded,
ct::core::StateVectorArray< STATE_DIM, SCALAR > &  x_shot_recorded,
ct::core::StateVectorArray< STATE_DIM, SCALAR > &  defects_recorded,
ct::core::ControlVectorArray< CONTROL_DIM, SCALAR > &  u_recorded,
scalar_t intermediateCost,
scalar_t finalCost,
scalar_t defectNorm,
scalar_t e_box_norm,
scalar_t e_gen_norm,
StateSubsteps substepsX,
ControlSubsteps substepsU,
std::atomic_bool *  terminationFlag = nullptr 
) const
protected

Check if controller with particular alpha is better.

compute costs

compute defects norm

References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeBoxConstraintErrorOfTrajectory(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeCostsOfTrajectory(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeGeneralConstraintErrorOfTrajectory(), ct::optcon::NLOptConSettings::debugPrint, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::delta_u_ff_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::delta_x_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::delta_x_ref_lqr_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::generalConstraints_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::inputBoxConstraints_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::K_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutShotsSingleThreaded(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::settings_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::stateBoxConstraints_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::u_ff_prev_, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::x_prev_.

Referenced by ct::optcon::NLOCBackendST< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::performLineSearch(), and ct::optcon::NLOCBackendMP< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::performLineSearch().

◆ acceptStep()

◆ updateFFController()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::updateFFController ( size_t  k)
protected

Update feedforward controller.

This function updates the feedforward Controller based on the previous calculation.

Parameters
kstep k

◆ computeDiscreteArrayNorm() [1/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
template<typename ARRAY_TYPE , size_t ORDER>
SCALAR ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeDiscreteArrayNorm ( const ARRAY_TYPE &  d) const
protected

compute norm of a discrete array (todo move to core)

◆ computeDiscreteArrayNorm() [2/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
template<typename ARRAY_TYPE , size_t ORDER>
SCALAR ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeDiscreteArrayNorm ( const ARRAY_TYPE &  a,
const ARRAY_TYPE &  b 
) const
protected

compute norm of difference between two discrete arrays (todo move to core)

◆ computeDefectsNorm() [2/2]

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
template<size_t ORDER>
SCALAR ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeDefectsNorm ( const StateVectorArray d) const
protected

compute the norm of the defects trajectory

Note that different kind of norms might be favorable for different cases. According to Nocedal and Wright, the l1-norm is "exact" (p.435), the l2-norm is smooth.

Member Data Documentation

◆ state_dim

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW const size_t ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::state_dim = STATE_DIM
static

◆ control_dim

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
const size_t ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::control_dim = CONTROL_DIM
static

◆ initialized_

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
bool ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::initialized_
protected

◆ configured_

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
bool ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::configured_
protected

◆ iteration_

◆ firstRollout_

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
bool ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::firstRollout_
protected

◆ settings_

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
Settings_t ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::settings_
protected

Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::acceptStep(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeCostFunction(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeGeneralConstraints(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeInputBoxConstraints(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeStateBoxConstraints(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeTimeHorizon(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeBoxConstraintErrorOfTrajectory(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeCostsOfTrajectory(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeGeneralConstraintErrorOfTrajectory(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeLinearizedConstraints(), ct::optcon::NLOCBackendST< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeLQApproximation(), ct::optcon::NLOCBackendMP< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeLQApproximation(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeSingleDefect(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::configure(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::executeLineSearch(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::executeLQApproximation(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::extractSolution(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::finishSolveLQProblem(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getNumStepsPerShot(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getSettings(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getTimeHorizon(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::initializeCostToGo(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lineSearch(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::logInitToMatlab(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::logToMatlab(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nominalRollout(), ct::optcon::NLOCBackendST< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::performLineSearch(), ct::optcon::NLOCBackendMP< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::performLineSearch(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::prepareSolveLQProblem(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::printSummary(), ct::optcon::NLOCBackendST< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutShots(), ct::optcon::NLOCBackendMP< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutShots(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutSingleShot(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::setInitialGuess(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::setInputBoxConstraintsForLQOCProblem(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::setStateBoxConstraintsForLQOCProblem(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::updateCosts(), and ct::optcon::NLOCBackendMP< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::~NLOCBackendMP().

◆ K_

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
int ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::K_
protected

Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::acceptStep(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeGeneralConstraints(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeTimeHorizon(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::checkProblem(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeBoxConstraintErrorOfTrajectory(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeCostsOfTrajectory(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeGeneralConstraintErrorOfTrajectory(), ct::optcon::NLOCBackendST< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeLQApproximation(), ct::optcon::NLOCBackendMP< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeLQApproximation(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeSingleDefect(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::executeLineSearch(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getNumSteps(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getNumStepsPerShot(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getTimeHorizon(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::initializeCostToGo(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lineSearch(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::logInitToMatlab(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::logToMatlab(), ct::optcon::NLOCBackendST< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::performLineSearch(), ct::optcon::NLOCBackendMP< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::performLineSearch(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutSingleShot(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::setInitialGuess().

◆ t_

◆ x_

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
StateVectorArray ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::x_
protected

the time trajectory

Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeCostFunction(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeGeneralConstraints(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeInitialState(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeInputBoxConstraints(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeStateBoxConstraints(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeTimeHorizon(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeLinearizedConstraints(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::doFullStepUpdate(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::executeLQApproximation(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::extractSolution(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getSolution(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getStateTrajectory(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::initializeCostToGo(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lineSearch(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::logInitToMatlab(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::logToMatlab(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nominalRollout(), ct::optcon::NLOCBackendST< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::performLineSearch(), ct::optcon::NLOCBackendMP< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::performLineSearch(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::printSummary(), ct::optcon::NLOCBackendST< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutShots(), ct::optcon::NLOCBackendMP< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutShots(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::setInitialGuess(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::setStateBoxConstraintsForLQOCProblem(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::updateCosts().

◆ xShot_

◆ d_

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
StateVectorArray ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::d_
protected

◆ x_prev_

◆ x_ref_lqr_

◆ u_ff_

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
ControlVectorArray ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::u_ff_
protected

reference for lqr

Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeCostFunction(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeGeneralConstraints(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeInputBoxConstraints(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeStateBoxConstraints(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeTimeHorizon(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::checkProblem(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeLinearizedConstraints(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::doFullStepUpdate(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::executeLQApproximation(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getControlTrajectory(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getSolution(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lineSearch(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::logInitToMatlab(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::logToMatlab(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nominalRollout(), ct::optcon::NLOCBackendST< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::performLineSearch(), ct::optcon::NLOCBackendMP< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::performLineSearch(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::printSummary(), ct::optcon::NLOCBackendMP< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutShots(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::setInitialGuess(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::setInputBoxConstraintsForLQOCProblem(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::updateCosts().

◆ u_ff_prev_

◆ L_

◆ delta_u_ff_

◆ delta_x_

◆ delta_x_ref_lqr_

◆ substepsX_

◆ substepsU_

◆ d_norm_

◆ e_box_norm_

◆ e_gen_norm_

◆ lx_norm_

◆ lu_norm_

◆ intermediateCostBest_

◆ finalCostBest_

◆ lowestCost_

◆ intermediateCostPrevious_

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
scalar_t ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::intermediateCostPrevious_
protected

◆ finalCostPrevious_

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
scalar_t ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::finalCostPrevious_
protected

◆ alphaBest_

◆ lqocProblem_

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
std::shared_ptr<LQOCProblem<STATE_DIM, CONTROL_DIM, SCALAR> > ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lqocProblem_
protected

shared pointer to the linear-quadratic optimal control problem that is constructed by NLOC

Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::acceptStep(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeGeneralConstraints(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeTimeHorizon(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeLinearizedConstraints(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::executeLQApproximation(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::finishSolveLQProblem(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::initializeCostToGo(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::logToMatlab(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::prepareSolveLQProblem(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::retrieveLastAffineModel(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::setInputBoxConstraintsForLQOCProblem(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::setStateBoxConstraintsForLQOCProblem(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::solveFullLQProblem().

◆ lqocSolver_

◆ systemInterface_

◆ costFunctions_

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
std::vector<typename OptConProblem_t::CostFunctionPtr_t> ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::costFunctions_
protected

◆ inputBoxConstraints_

◆ stateBoxConstraints_

◆ generalConstraints_

◆ lqpCounter_

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
size_t ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lqpCounter_
protected

◆ policy_

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR = double, bool CONTINUOUS = true>
NLOCBackendBase::Policy_t ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::policy_
protected

The policy. currently only for returning the result, should eventually replace L_ and u_ff_ (todo)

Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getSolution().

◆ summaryAllIterations_


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