- 3.0.2 optimal control module.
ct::optcon::NLOptConSettings Class Reference

Settings for the NLOptCon algorithm. More...

#include <NLOptConSettings.hpp>

Public Types

enum  NLOCP_ALGORITHM {
  GNMS = 0, ILQR, MS_ILQR, SS_OL,
  SS_CL, GNMS_M_OL, GNMS_M_CL, NUM_TYPES
}
 algorithm types for solving the NLOC problem More...
 
enum  LQOCP_SOLVER { GNRICCATI_SOLVER = 0, HPIPM_SOLVER = 1 }
 the linear optimal control problem solver in the background More...
 
using APPROXIMATION = typename core::SensitivityApproximationSettings::APPROXIMATION
 

Public Member Functions

 NLOptConSettings ()
 NLOptCon Settings default constructor. More...
 
int computeK (double timeHorizon) const
 log to matlab (true/false) More...
 
double getSimulationTimestep () const
 compute the simulation timestep More...
 
bool closedLoopShooting () const
 return if this is a closed-loop shooting algorithm (or not) More...
 
bool isSingleShooting () const
 return if this is a single-shooting algorithm (or not) More...
 
void print () const
 print the current NLOptCon settings to console More...
 
bool parametersOk () const
 perform a quick check if the given NLOptCon settings fulfil minimum requirements More...
 
void load (const std::string &filename, bool verbose=true, const std::string &ns="alg")
 load NLOptCon Settings from file More...
 

Static Public Member Functions

static NLOptConSettings fromConfigFile (const std::string &filename, bool verbose=true, const std::string &ns="alg")
 load settings from config file and return as settings struct More...
 

Public Attributes

ct::core::IntegrationType integrator
 
APPROXIMATION discretization
 which integrator to use during the NLOptCon forward rollout More...
 
bool timeVaryingDiscretization
 
NLOCP_ALGORITHM nlocp_algorithm
 
LQOCP_SOLVER lqocp_solver
 which nonlinear optimal control algorithm is to be used More...
 
std::string loggingPrefix
 the solver for the linear-quadratic optimal control problem More...
 
double epsilon
 the prefix to be stored before the matfile name for logging More...
 
double dt
 Eigenvalue correction factor for Hessian regularization. More...
 
int K_sim
 sampling time for the control input (seconds) More...
 
int K_shot
 number of sub-integration-steps More...
 
double min_cost_improvement
 duration of a shot as an integer multiple of dt More...
 
double maxDefectSum
 minimum cost improvement between two interations to assume convergence More...
 
double meritFunctionRho
 maximum sum of squared defects (assume covergence if lower than this number) More...
 
double meritFunctionRhoConstraints
 trade off between internal (defect)constraint violation and cost More...
 
int max_iterations
 trade off between external (general and path) constraint violation and cost More...
 
bool fixedHessianCorrection
 the maximum admissible number of NLOptCon main iterations More...
 
bool recordSmallestEigenvalue
 perform Hessian regularization by incrementing the eigenvalues by epsilon. More...
 
int nThreads
 save the smallest eigenvalue of the Hessian More...
 
size_t nThreadsEigen
 number of threads, for MP version More...
 
LineSearchSettings lineSearchSettings
 number of threads for eigen parallelization (applies both to MP and ST) Note. in order to activate Eigen parallelization, compile with '-fopenmp' More...
 
LQOCSolverSettings lqoc_solver_settings
 the line search settings More...
 
bool debugPrint
 
bool printSummary
 
bool useSensitivityIntegrator
 
bool logToMatlab
 

Detailed Description

Member Typedef Documentation

◆ APPROXIMATION

Member Enumeration Documentation

◆ NLOCP_ALGORITHM

algorithm types for solving the NLOC problem

Enumerator
GNMS 
ILQR 

Gauss-Newton Multiple Shooting (shooting interval = control interval)

MS_ILQR 

Classical iLQR (1 shooting interval equal to problem horizon)

SS_OL 

multiple-shooting iLQR

SS_CL 

Classical (open-loop) Single Shooting.

GNMS_M_OL 

Closed-loop single shooting.

GNMS_M_CL 

GNMS(M) with open-loop shooting.

NUM_TYPES 

GNMS(M) with closed-loop shooting.

◆ LQOCP_SOLVER

the linear optimal control problem solver in the background

Enumerator
GNRICCATI_SOLVER 
HPIPM_SOLVER 

Constructor & Destructor Documentation

◆ NLOptConSettings()

ct::optcon::NLOptConSettings::NLOptConSettings ( )
inline

NLOptCon Settings default constructor.

sets all settings to default values.

References RK4.

Member Function Documentation

◆ computeK()

int ct::optcon::NLOptConSettings::computeK ( double  timeHorizon) const
inline

log to matlab (true/false)

compute the number of discrete time steps for an arbitrary input time interval

Parameters
timeHorizonthe time horizon of interest, e.g. overall optimal control time horizon or shot-length
Returns
the resulting number of steps, minimum 1 steps long
Todo:
naming it K is confusing, should better be N.
Examples:
LinearSystemTest.h, NLOC.cpp, NLOC_boxConstrained.cpp, NLOC_generalConstrained.cpp, NLOC_MPC.cpp, NonlinearSystemTest.h, and switched_continuous_optcon.cpp.

Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeTimeHorizon(), generateSolver(), main(), and ct::optcon::example::TEST().

◆ getSimulationTimestep()

double ct::optcon::NLOptConSettings::getSimulationTimestep ( ) const
inline

◆ closedLoopShooting()

bool ct::optcon::NLOptConSettings::closedLoopShooting ( ) const
inline

return if this is a closed-loop shooting algorithm (or not)

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

◆ isSingleShooting()

bool ct::optcon::NLOptConSettings::isSingleShooting ( ) const
inline

◆ print()

void ct::optcon::NLOptConSettings::print ( ) const
inline

print the current NLOptCon settings to console

References ct::optcon::LineSearchSettings::print(), and ct::optcon::LQOCSolverSettings::print().

◆ parametersOk()

bool ct::optcon::NLOptConSettings::parametersOk ( ) const
inline

perform a quick check if the given NLOptCon settings fulfil minimum requirements

Warning
This check cannot guarantee that the control problem is well parameterized

References ct::optcon::LineSearchSettings::parametersOk().

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

◆ load()

void ct::optcon::NLOptConSettings::load ( const std::string &  filename,
bool  verbose = true,
const std::string &  ns = "alg" 
)
inline

load NLOptCon Settings from file

Parameters
filenamepath to the settings file
verboseprint out settings after reading them
ns(optional) namspace of parameter file
Examples:
NLOC.cpp, NLOC_generalConstrained.cpp, and NonlinearSystemTest.h.

References ct::optcon::LineSearchSettings::load(), ct::optcon::LQOCSolverSettings::load(), ct::optcon::LineSearchSettings::print(), and ct::optcon::example::verbose.

Referenced by fromConfigFile(), main(), and ct::optcon::example::TEST().

◆ fromConfigFile()

static NLOptConSettings ct::optcon::NLOptConSettings::fromConfigFile ( const std::string &  filename,
bool  verbose = true,
const std::string &  ns = "alg" 
)
inlinestatic

load settings from config file and return as settings struct

Parameters
filenamethe path to the settings file
verboseprint settings
ns(optional) settings namespace
Returns
the newly generated settings struct

References load().

Member Data Documentation

◆ integrator

◆ discretization

◆ timeVaryingDiscretization

◆ nlocp_algorithm

◆ lqocp_solver

◆ loggingPrefix

◆ epsilon

◆ dt

double ct::optcon::NLOptConSettings::dt

Eigenvalue correction factor for Hessian regularization.

Examples:
LinearSystemTest.h, NLOC.cpp, NLOC_boxConstrained.cpp, NLOC_generalConstrained.cpp, NLOC_MPC.cpp, NonlinearSystemTest.h, switched_continuous_optcon.cpp, and SymplecticTest.h.

Referenced by ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeGeneralConstraints(), ct::optcon::OptconContinuousSystemInterface< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR >::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 >::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::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::executeLQApproximation(), generateSolver(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::getTimeHorizon(), ct::optcon::OptconContinuousSystemInterface< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR >::initialize(), 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 >::logInitToMatlab(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::logToMatlab(), main(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::setInitialGuess(), ct::optcon::example::symplecticTest(), and ct::optcon::example::TEST().

◆ K_sim

◆ K_shot

◆ min_cost_improvement

double ct::optcon::NLOptConSettings::min_cost_improvement

◆ maxDefectSum

double ct::optcon::NLOptConSettings::maxDefectSum

minimum cost improvement between two interations to assume convergence

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

◆ meritFunctionRho

◆ meritFunctionRhoConstraints

◆ max_iterations

int ct::optcon::NLOptConSettings::max_iterations

trade off between external (general and path) constraint violation and cost

Examples:
NLOC_boxConstrained.cpp, NLOC_MPC.cpp, switched_continuous_optcon.cpp, and SymplecticTest.h.

Referenced by generateSolver(), main(), ct::optcon::example::symplecticTest(), and ct::optcon::example::TEST().

◆ fixedHessianCorrection

bool ct::optcon::NLOptConSettings::fixedHessianCorrection

the maximum admissible number of NLOptCon main iterations

Warning
make sure to select this number high enough allow for convergence
Examples:
LinearSystemTest.h, and SymplecticTest.h.

Referenced by ct::optcon::GNRiccatiSolver< STATE_DIM, CONTROL_DIM, SCALAR >::designController(), ct::optcon::example::symplecticTest(), ct::optcon::example::TEST(), and timeSingleSolve().

◆ recordSmallestEigenvalue

◆ nThreads

int ct::optcon::NLOptConSettings::nThreads

save the smallest eigenvalue of the Hessian

Examples:
LinearSystemTest.h, NLOC_boxConstrained.cpp, switched_continuous_optcon.cpp, and SymplecticTest.h.

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::OptconDiscreteSystemInterface< STATE_DIM, CONTROL_DIM, SCALAR >::changeLinearSystem(), ct::optcon::OptconContinuousSystemInterface< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR >::changeLinearSystem(), ct::optcon::OptconDiscreteSystemInterface< STATE_DIM, CONTROL_DIM, SCALAR >::changeNonlinearSystem(), ct::optcon::OptconContinuousSystemInterface< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR >::changeNonlinearSystem(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::changeStateBoxConstraints(), 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::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::configure(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::configure(), generateSolver(), ct::optcon::OptconDiscreteSystemInterface< STATE_DIM, CONTROL_DIM, SCALAR >::initialize(), ct::optcon::OptconContinuousSystemInterface< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR >::initialize(), ct::optcon::NLOptConSolver< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::initialize(), 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 >::logInitToMatlab(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::logToMatlab(), main(), 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::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 >::setInputBoxConstraintsForLQOCProblem(), ct::optcon::NLOCBackendBase< STATE_DIM, CONTROL_DIM, P_DIM, V_DIM, SCALAR, CONTINUOUS >::setStateBoxConstraintsForLQOCProblem(), ct::optcon::example::symplecticTest(), ct::optcon::example::TEST(), 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().

◆ nThreadsEigen

◆ lineSearchSettings

◆ lqoc_solver_settings

LQOCSolverSettings ct::optcon::NLOptConSettings::lqoc_solver_settings

◆ debugPrint

◆ printSummary

◆ useSensitivityIntegrator

◆ logToMatlab


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