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

#include <NLOCBackendST.hpp>

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

Public Types

typedef Base::OptConProblem_t OptConProblem_t
 
- Public Types inherited from ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >
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

 NLOCBackendST (const OptConProblem_t &optConProblem, const NLOptConSettings &settings)
 
 NLOCBackendST (const OptConProblem_t &optConProblem, const std::string &settingsFile, bool verbose=true, const std::string &ns="alg")
 
virtual ~NLOCBackendST ()
 
- Public Member Functions inherited from ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >
 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...
 
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...
 
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...
 
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
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS > Base
 

Protected Member Functions

virtual void computeLQApproximation (size_t firstIndex, size_t lastIndex) override
 build LQ approximation around trajectory (linearize dynamics and general constraints, quadratize cost, etc) More...
 
virtual void rolloutShots (size_t firstIndex, size_t lastIndex) override
 integrates the specified shots and computes the corresponding defects More...
 
SCALAR performLineSearch () override
 performLineSearch: execute the line search, possibly with different threading schemes More...
 
- Protected Member Functions inherited from ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >
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...
 

Additional Inherited Members

- Static Public Attributes inherited from ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >
static EIGEN_MAKE_ALIGNED_OPERATOR_NEW const size_t state_dim = STATE_DIM
 
static const size_t control_dim = CONTROL_DIM
 
- Protected Attributes inherited from ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >
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::NLOCBackendST< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >

NLOC Backend for Single-Threaded case

Member Typedef Documentation

◆ 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 Base::OptConProblem_t ct::optcon::NLOCBackendST< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::OptConProblem_t

Constructor & Destructor Documentation

◆ NLOCBackendST() [1/2]

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

◆ NLOCBackendST() [2/2]

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

◆ ~NLOCBackendST()

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

Member Function Documentation

◆ computeLQApproximation()

◆ rolloutShots()

◆ performLineSearch()

template<size_t STATE_DIM, size_t CONTROL_DIM, size_t P_DIM, size_t V_DIM, typename SCALAR , bool CONTINUOUS>
SCALAR ct::optcon::NLOCBackendST< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::performLineSearch ( )
overrideprotectedvirtual

performLineSearch: execute the line search, possibly with different threading schemes

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

References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::acceptStep(), ct::optcon::LineSearchSettings::alpha_0, 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::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 >::executeLineSearch(), 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::LineSearchSettings::maxIterations, ct::optcon::LineSearchSettings::n_alpha, ct::optcon::NLOptConSettings::nThreads, 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::core::DiscreteArray< T, Alloc >::swap(), 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_, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::xShot_.

Member Data Documentation

◆ Base

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 typedef NLOCBackendBase<STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS> ct::optcon::NLOCBackendST< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::Base

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