- 3.0.2 optimal control module.
|
C++ implementation of GNMS. More...
#include <NLOCBackendBase.hpp>
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_t & | getSettings () 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, SCALAR > | getStateTrajectory () const |
const core::ControlTrajectory< CONTROL_DIM, SCALAR > | getControlTrajectory () const |
const Policy_t & | getSolution () |
const TimeArray & | getTimeArray () |
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< SCALAR > | t_ |
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< SCALAR > | summaryAllIterations_ |
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)
typedef NLOptConSettings ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::Settings_t |
typedef ct::core::StateFeedbackController<STATE_DIM, CONTROL_DIM, SCALAR> ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::Policy_t |
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 |
typedef LQOCProblem<STATE_DIM, CONTROL_DIM, SCALAR> ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::LQOCProblem_t |
typedef LQOCSolver<STATE_DIM, CONTROL_DIM, SCALAR> ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::LQOCSolver_t |
typedef ct::core::StateVectorArray<STATE_DIM, SCALAR> ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::StateVectorArray |
typedef std::shared_ptr<StateVectorArray> ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::StateVectorArrayPtr |
typedef ct::core::ControlVectorArray<CONTROL_DIM, SCALAR> ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::ControlVectorArray |
typedef std::shared_ptr<ControlVectorArray> ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::ControlVectorArrayPtr |
typedef std::vector<StateVectorArrayPtr, Eigen::aligned_allocator<StateVectorArrayPtr> > ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::StateSubsteps |
typedef std::shared_ptr<StateSubsteps> ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::StateSubstepsPtr |
typedef std::vector<ControlVectorArrayPtr, Eigen::aligned_allocator<ControlVectorArrayPtr> > ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::ControlSubsteps |
typedef std::shared_ptr<ControlSubsteps> ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::ControlSubstepsPtr |
typedef OptconSystemInterface<STATE_DIM, CONTROL_DIM, OptConProblem_t, SCALAR> ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::systemInterface_t |
typedef std::shared_ptr<systemInterface_t> ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::systemInterfacePtr_t |
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::ControlMatrix = ct::core::ControlMatrix<CONTROL_DIM, SCALAR> |
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::ControlMatrixArray = ct::core::ControlMatrixArray<CONTROL_DIM, SCALAR> |
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::StateMatrixArray = ct::core::StateMatrixArray<STATE_DIM, SCALAR> |
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::StateControlMatrixArray = ct::core::StateControlMatrixArray<STATE_DIM, CONTROL_DIM, SCALAR> |
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::FeedbackArray = ct::core::FeedbackArray<STATE_DIM, CONTROL_DIM, SCALAR> |
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::TimeArray = ct::core::tpl::TimeArray<SCALAR> |
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::state_matrix_t = Eigen::Matrix<SCALAR, STATE_DIM, STATE_DIM> |
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::control_matrix_t = Eigen::Matrix<SCALAR, CONTROL_DIM, CONTROL_DIM> |
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> |
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> |
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::state_vector_t = core::StateVector<STATE_DIM, SCALAR> |
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::control_vector_t = core::ControlVector<CONTROL_DIM, SCALAR> |
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::feedback_matrix_t = core::FeedbackMatrix<STATE_DIM, CONTROL_DIM, SCALAR> |
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::scalar_t = SCALAR |
using ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::scalar_array_t = std::vector<SCALAR, Eigen::aligned_allocator<SCALAR> > |
ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::NLOCBackendBase | ( | const OptConProblem_t & | optConProblem, |
const Settings_t & | settings | ||
) |
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" |
||
) |
ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::NLOCBackendBase | ( | const systemInterfacePtr_t & | systemInterface, |
const Settings_t & | settings | ||
) |
References 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 >::configure(), and 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 >::NLOCBackendBase | ( | const systemInterfacePtr_t & | systemInterface, |
const std::string & | settingsFile, | ||
bool | verbose = true , |
||
const std::string & | ns = "alg" |
||
) |
|
virtual |
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 | ||
) |
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 | ||
) |
|
virtual |
configure the solver
Configure the solver
settings | solver settings |
References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::configured_, ct::optcon::NLOptConSettings::lqocp_solver, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lqocSolver_, ct::optcon::NLOptConSettings::nThreads, ct::optcon::NLOptConSettings::nThreadsEigen, ct::optcon::NLOptConSettings::parametersOk(), 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_, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::systemInterface_.
Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::NLOCBackendBase().
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 |
get the current SLQsolver settings
References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::settings_.
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_.
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().
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_.
SCALAR ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getTimeHorizon | ( | ) |
int ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getNumSteps | ( | ) |
int ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getNumStepsPerShot | ( | ) | const |
References ct::optcon::NLOptConSettings::isSingleShooting(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::K_, ct::optcon::NLOptConSettings::K_shot, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::settings_.
Referenced by 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 >::rolloutShotsSingleThreaded(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutSingleShot().
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeInitialState | ( | const core::StateVector< STATE_DIM, SCALAR > & | x0 | ) |
Change the initial state for the optimal control problem.
References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::reset(), x0, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::x_.
Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::NLOCBackendBase().
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeCostFunction | ( | const typename OptConProblem_t::CostFunctionPtr_t & | cf | ) |
Change the cost function.
References 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 >::costFunctions_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::finalCostBest_, i, 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::lineSearchSettings, ct::optcon::NLOptConSettings::nThreads, 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_, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::x_.
Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::NLOCBackendBase().
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeNonlinearSystem | ( | const typename OptConProblem_t::DynamicsPtr_t & | dyn | ) |
Change the nonlinear system.
References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::systemInterface_.
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeLinearSystem | ( | const typename OptConProblem_t::LinearPtr_t & | lin | ) |
Change the linear system.
References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::systemInterface_.
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeInputBoxConstraints | ( | const typename OptConProblem_t::ConstraintPtr_t & | con | ) |
Change the input box constraints.
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 >::e_box_norm_, i, 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 >::iteration_, ct::optcon::NLOptConSettings::lineSearchSettings, ct::optcon::NLOptConSettings::nThreads, 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 >::settings_, ct::optcon::LineSearchSettings::type, 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_.
Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::NLOCBackendBase().
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeStateBoxConstraints | ( | const typename OptConProblem_t::ConstraintPtr_t & | con | ) |
Change the state box constraints.
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 >::e_box_norm_, i, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::iteration_, ct::optcon::NLOptConSettings::lineSearchSettings, ct::optcon::NLOptConSettings::nThreads, 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 >::settings_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::stateBoxConstraints_, ct::optcon::LineSearchSettings::type, 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_.
Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::NLOCBackendBase().
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeGeneralConstraints | ( | const typename OptConProblem_t::ConstraintPtr_t & | con | ) |
Change the general constraints.
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 >::e_gen_norm_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::generalConstraints_, i, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::iteration_, 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 >::lqocProblem_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lqocSolver_, ct::optcon::NLOptConSettings::nThreads, 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_, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::x_.
Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::NLOCBackendBase().
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.
References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::systemInterface_.
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 |
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.
References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::systemInterface_.
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 |
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.
References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::costFunctions_.
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 |
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.
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 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 |
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 |
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.
References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::generalConstraints_.
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 |
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.
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_.
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::logInitToMatlab | ( | ) |
log the initial guess to Matlab
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 >::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::NLOptConSettings::nThreads, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::settings_, ct::core::DiscreteArray< T, Alloc >::toImplementation(), 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_.
SCALAR ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getCost | ( | ) | const |
return the cost of the solution of the current iteration
References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::finalCostBest_, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::intermediateCostBest_.
Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::logInitToMatlab(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::logToMatlab().
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_.
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::reset | ( | ) |
References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::d_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 >::finalCostPrevious_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::firstRollout_, 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::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::iteration_, 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_, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::resetDefects().
Referenced by 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 >::configure(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::setInitialGuess().
const core::StateTrajectory< STATE_DIM, SCALAR > ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getStateTrajectory | ( | ) | const |
References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::t_, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::x_.
const core::ControlTrajectory< CONTROL_DIM, SCALAR > ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getControlTrajectory | ( | ) | const |
References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::t_, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::u_ff_.
const NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::Policy_t & ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getSolution | ( | ) |
References 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 >::policy_, 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 >::update(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::x_.
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 | ( | ) |
bool ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::isConfigured | ( | ) |
bool ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::isInitialized | ( | ) |
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_.
|
virtual |
the prepare Solve LQP Problem method is intended for a special use-case: unconstrained GNMS with pre-solving of the
References i, ct::optcon::NLOptConSettings::lqocp_solver, 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 >::lqpCounter_, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::settings_.
|
virtual |
References i, ct::optcon::NLOptConSettings::lqocp_solver, 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 >::lqpCounter_, 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 >::solveFullLQProblem().
|
virtual |
solve Full LQProblem, e.g. to be used with HPIPM or if we have a constrained problem
References 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_, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lqpCounter_.
Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::finishSolveLQProblem().
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::extractSolution | ( | ) |
extract relevant quantities for the following rollout/solution update step from the LQ solver
References 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 >::L_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lqocSolver_, ct::optcon::NLOptConSettings::nlocp_algorithm, ct::core::DiscreteArray< T, Alloc >::setConstant(), 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 >::x_, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::x_ref_lqr_.
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::updateCosts | ( | ) |
compute costs of solution candidate
References 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 >::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 >::intermediateCostBest_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::intermediateCostPrevious_, 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 >::u_ff_, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::x_.
Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lineSearch().
bool ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::nominalRollout | ( | ) |
nominal rollout using default thread and member variables for the results. // todo maybe rename (initial rollout?)
References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::firstRollout_, ct::optcon::NLOptConSettings::nThreads, 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 >::settings_, 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_.
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::checkProblem | ( | ) |
check problem for consistency
References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::K_, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::u_ff_.
size_t & ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::iteration | ( | ) |
return the current iteration number
References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::iteration_.
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.
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_.
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_.
|
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 >.
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::setInputBoxConstraintsForLQOCProblem | ( | ) |
sets the box constraints for the entire time horizon including terminal stage
References 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 >::lqocProblem_, ct::optcon::NLOptConSettings::nThreads, 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 >::u_ff_.
Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeInputBoxConstraints().
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::setStateBoxConstraintsForLQOCProblem | ( | ) |
References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lqocProblem_, 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 >::stateBoxConstraints_, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::x_.
Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeStateBoxConstraints().
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::resetDefects | ( | ) |
reset all defects to zero
References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::d_, and ct::core::DiscreteArray< T, Alloc >::setConstant().
Referenced by 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 >::lineSearch(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::reset().
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeDefectsNorm | ( | ) |
|
pure virtual |
integrates the specified shots and computes the corresponding defects
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 >.
Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lineSearch().
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 |
do a single threaded rollout and defect computation of the shots - useful for line-search
make sure all intermediate entries in the defect trajectory are zero
References 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 >::getNumStepsPerShot(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutSingleShot(), and ct::core::DiscreteArray< T, Alloc >::setConstant().
Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::executeLineSearch().
|
pure virtual |
performLineSearch: execute the line search, possibly with different threading schemes
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 >.
Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lineSearch().
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::doFullStepUpdate | ( | ) |
simple full-step update for state and feedforward control (used for MPC-mode!)
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 >::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 >::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 >::x_ref_lqr_.
Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lineSearch().
void ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::logSummaryToMatlab | ( | const std::string & | fileName | ) |
const SummaryAllIterations< SCALAR > & ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getSummary | ( | ) | const |
|
protected |
integrate the individual shots
determine index where to stop at the latest
initialize integration variable
"overwrite" x_local
fill in terminal state if required
u_local | the starting index of the shot |
substepsX | the value at the end of each integration interval |
References ct::optcon::NLOptConSettings::closedLoopShooting(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getNumStepsPerShot(), i, 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 >::settings_, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::systemInterface_.
Referenced by 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 >::rolloutShots(), ct::optcon::NLOCBackendMP< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutShots(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutShotsSingleThreaded().
|
protected |
computes the defect between shot and trajectory
k | index of the shot under consideration |
x_local | the state trajectory |
xShot | the shot trajectory |
d | the defect trajectory |
compute the index where the next shot starts (respect total number of stages)
else ... all other entries of d remain zero.
References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::K_, ct::optcon::NLOptConSettings::K_shot, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::settings_.
Referenced by 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(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutShotsSingleThreaded().
|
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 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.
threadId | the id of the worker thread |
k | step k |
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().
|
protected |
Computes the linearized general constraints at a specific point of the trajectory.
This function calculates the linearization, i.e. matrices d, C and D in at a specific point of the trajectory
threadId | the id of the worker thread |
k | step k |
References ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::C_, ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::D_, ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::d_lb_, ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::d_ub_, dt, ct::optcon::NLOptConSettings::dt, 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 >::lqocProblem_, ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::ng_, 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 >::u_ff_, and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::x_.
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().
|
protected |
Initializes cost to go.
This function initializes the cost-to-go function at time K.
References ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::C_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::costFunctions_, ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::D_, ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::d_lb_, ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::d_ub_, ct::optcon::NLOptConSettings::dt, 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 >::K_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lqocProblem_, ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::ng_, ct::optcon::NLOptConSettings::nThreads, ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::Q_, ct::optcon::LQOCProblem< STATE_DIM, CONTROL_DIM, SCALAR >::qv_, 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 >::x_.
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().
|
protected |
Computes cost to go.
This function computes the cost-to-go function for all times t<t_K
k | step k |
|
protected |
Design controller.
This function designes the LQR and feedforward controller at time k.
k | step k |
|
protected |
Compute cost for a given set of state and input trajectory.
Compute cost for a given set of state and input trajectory
threadId | the ID of the thread |
x_local | the state trajectory |
u_local | the control trajectory |
intermediateCost | the accumulated intermediate cost |
finalCost | the accumulated final cost |
References ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::costFunctions_, ct::optcon::NLOptConSettings::dt, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::K_, 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 >::changeCostFunction(), 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 >::setInitialGuess(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::updateCosts().
|
protected |
Compute box constraint violations for a given set of state and input trajectory.
threadId | the ID of the thread |
x_local | the state trajectory |
u_local | the control trajectory |
e_tot | the 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().
|
protected |
Compute general constraint violations for a given set of state and input trajectory.
threadId | the ID of the thread |
x_local | the state trajectory |
u_local | the control trajectory |
e_tot | the total accumulated general constraint violation |
References ct::optcon::NLOptConSettings::dt, 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 >::K_, 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 >::changeGeneralConstraints(), 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 >::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().
|
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().
|
protected |
in case of line-search compute new merit and check if to accept step. Returns true if accept step
References ct::optcon::LineSearchSettings::armijo_parameter, i, 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 >::lqocProblem_, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lqocSolver_, lv, ct::optcon::NLOptConSettings::meritFunctionRho, ct::optcon::NLOptConSettings::meritFunctionRhoConstraints, ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::settings_, and ct::optcon::LineSearchSettings::type.
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().
|
protected |
Update feedforward controller.
This function updates the feedforward Controller based on the previous calculation.
k | step k |
|
protected |
compute norm of a discrete array (todo move to core)
|
protected |
compute norm of difference between two discrete arrays (todo move to core)
|
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.
|
static |
|
static |
|
protected |
|
protected |
|
protected |
current iteration
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 >::iteration(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::printSummary(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::reset(), and ct::optcon::NLOCBackendMP< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::~NLOCBackendMP().
|
protected |
|
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().
|
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().
|
protected |
the number of stages in the overall OptConProblem
Referenced by 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 >::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 >::getStateTrajectory(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getTimeArray(), 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 >::setInitialGuess().
|
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().
|
protected |
state array variables
Referenced by 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 >::executeLQApproximation(), 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::NLOCBackendST< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutShots(), and ct::optcon::NLOCBackendMP< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutShots().
|
protected |
rolled-out state (at the end of a time step forward)
Referenced by 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 >::computeDefectsNorm(), 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 >::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 >::printSummary(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::resetDefects(), ct::optcon::NLOCBackendST< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutShots(), and ct::optcon::NLOCBackendMP< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutShots().
|
protected |
defects in between end of rollouts and subsequent state decision vars
Referenced by 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 >::executeLineSearch(), 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 >::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(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::setInitialGuess().
|
protected |
state array from previous iteration
Referenced by 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 >::doFullStepUpdate(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::extractSolution(), ct::optcon::NLOCBackendMP< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutShots(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::setInitialGuess().
|
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().
|
protected |
feed forward controls
Referenced by 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 >::executeLineSearch(), 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 >::nominalRollout(), 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().
|
protected |
feed forward controls from previous iteration
Referenced by 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 >::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 >::rolloutSingleShot(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::setInitialGuess().
|
protected |
time-varying lqr feedback
Referenced by 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 >::doFullStepUpdate(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::executeLineSearch(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::extractSolution().
|
protected |
pointer to control increment
Referenced by 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 >::doFullStepUpdate(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::executeLineSearch(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::extractSolution().
|
protected |
pointer to state increment
Referenced by 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 >::doFullStepUpdate(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::executeLineSearch(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::extractSolution().
|
protected |
state array from previous iteration
Referenced by 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 >::executeLQApproximation(), 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(), and ct::optcon::NLOCBackendMP< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutShots().
|
protected |
state substeps recorded by integrator during rollouts
Referenced by 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 >::executeLQApproximation(), 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(), and ct::optcon::NLOCBackendMP< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutShots().
|
protected |
control substeps recorded by integrator during rollouts
Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::computeDefectsNorm(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getTotalDefect(), 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(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::reset().
|
protected |
sum of the norms of all defects (internal constraint)
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 >::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(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::printSummary().
|
protected |
sum of the norms of all box constraint violations
Referenced by 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 >::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(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::printSummary().
|
protected |
sum of the norms of all general constraint violations
Referenced by 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 >::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 >::printSummary(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::reset().
|
protected |
sum of the norms of state update
Referenced by 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 >::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 >::printSummary(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::reset().
|
protected |
sum of the norms of control update
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 >::getCost(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lineSearch(), 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::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 >::setInitialGuess(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::updateCosts().
|
protected |
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 >::getCost(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lineSearch(), 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::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 >::setInitialGuess(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::updateCosts().
|
protected |
Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::lineSearch(), 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().
|
protected |
costs of the previous iteration, required to determine convergence
Referenced by 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 >::setInitialGuess(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::updateCosts().
|
protected |
Referenced by 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 >::setInitialGuess(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::updateCosts().
|
protected |
Referenced by 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 >::lineSearch(), 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().
|
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().
|
protected |
shared pointer to the linear-quadratic optimal control solver, that solves above LQOCP
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 >::configure(), 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 >::prepareSolveLQProblem(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::printSummary(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::solveFullLQProblem().
|
protected |
pointer to instance of the system interface
Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeLinearSystem(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeNonlinearSystem(), 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 >::configure(), 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 >::getLinearSystemsInstances(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getNonlinearSystemsInstances(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::NLOCBackendBase(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::rolloutSingleShot().
|
protected |
of the following objects, we have nThreads+1 instantiations in form of a vector. Every instantiation is dedicated to a certain thread in the multi-thread implementation
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 >::computeCostsOfTrajectory(), 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 >::getCostFunctionInstances(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::initializeCostToGo().
|
protected |
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 >::computeBoxConstraintErrorOfTrajectory(), 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 >::getInputBoxConstraintsInstances(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::setInputBoxConstraintsForLQOCProblem().
|
protected |
Referenced by 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 >::computeBoxConstraintErrorOfTrajectory(), 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 >::getStateBoxConstraintsInstances(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::setStateBoxConstraintsForLQOCProblem().
|
protected |
Referenced by 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 >::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 >::executeLineSearch(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getGeneralConstraintsInstances(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::initializeCostToGo().
|
protected |
a counter used to identify lqp problems in derived classes, i.e. for thread management in MP
Referenced by 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 >::prepareSolveLQProblem(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::solveFullLQProblem(), and ct::optcon::NLOCBackendMP< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::~NLOCBackendMP().
|
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().
|
protected |
Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getSummary(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::logSummaryToMatlab(), and ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::printSummary().