#include <acado/utils/acado_namespace_macros.hpp>

Go to the source code of this file.
Classes | |
| class | returnValue |
| Allows to pass back messages to the calling function. More... | |
Macros | |
| #define | BT_FALSE false |
| #define | BT_TRUE true |
| #define | NO false |
| #define | YES true |
Typedefs | |
| typedef bool | BooleanType |
| typedef void(* | cFcnDPtr) (int number, double *x, double *seed, double *f, double *df, void *userData) |
| typedef void(* | cFcnPtr) (double *x, double *f, void *userData) |
Variables | |
| BEGIN_NAMESPACE_ACADO typedef unsigned int | uint |
| #define BT_FALSE false |
Aliasing false.
Definition at line 49 of file acado_types.hpp.
| #define BT_TRUE true |
Aliasing true.
Definition at line 47 of file acado_types.hpp.
| #define NO false |
Aliasing no.
Definition at line 53 of file acado_types.hpp.
| #define YES true |
Aliasing yes.
Definition at line 51 of file acado_types.hpp.
| typedef bool BooleanType |
Boolean type aliasing.
Definition at line 45 of file acado_types.hpp.
| typedef void(* cFcnDPtr) (int number, double *x, double *seed, double *f, double *df, void *userData) |
Function pointer type for derivatives given as C source code.
Definition at line 59 of file acado_types.hpp.
| typedef void(* cFcnPtr) (double *x, double *f, void *userData) |
Function pointer type for functions given as C source code.
Definition at line 56 of file acado_types.hpp.
Defines all possible relaxation type used in DAE integration routines
| Enumerator | |
|---|---|
| ART_EXPONENTIAL | |
| ART_ADAPTIVE_POLYNOMIAL | |
| ART_UNKNOWN | |
Definition at line 136 of file acado_types.hpp.
| enum BlockName |
Summarizes all possible block names.
| Enumerator | |
|---|---|
| BN_DEFAULT | |
| BN_SIMULATION_ENVIRONMENT | |
| BN_PROCESS | |
| BN_ACTUATOR | |
| BN_SENSOR | |
| BN_CONTROLLER | |
| BN_ESTIMATOR | |
| BN_REFERENCE_TRAJECTORY | |
| BN_CONTROL_LAW | |
Definition at line 695 of file acado_types.hpp.
| enum BlockStatus |
Summarizes all possible states of a block or algorithmic module.
Definition at line 710 of file acado_types.hpp.
| enum ClockStatus |
Summarizes all possible states of a clock.
| Enumerator | |
|---|---|
| CS_NOT_INITIALIZED | Clock has not been initialized. |
| CS_RUNNING | Clock is running. |
| CS_STOPPED | Clock has been initialized and stopped. |
Definition at line 720 of file acado_types.hpp.
Definition at line 815 of file acado_types.hpp.
| enum CondensingStatus |
Summarizes all possible states of the condensing used within condensing based CP solvers.
Definition at line 685 of file acado_types.hpp.
| enum CondensingType |
Condensing type
| Enumerator | |
|---|---|
| CT_LIFTING | Sensitivities are lifted |
| CT_SPARSE | Sensitivities are sparse |
Definition at line 594 of file acado_types.hpp.
| enum ConicSolverStatus |
Summarises all possible states of the Conic Solver.
Definition at line 646 of file acado_types.hpp.
Summarises all possible ways of discretising the system's states.
Definition at line 210 of file acado_types.hpp.
| enum CurvatureType |
Defines all possible curvature types.
Definition at line 179 of file acado_types.hpp.
| Enumerator | |
|---|---|
| DET_ODE | ordinary differential equation |
| DET_DAE | differential algebraic equation |
| DET_UNKNOWN | unknown |
Definition at line 190 of file acado_types.hpp.
Defines .
| Enumerator | |
|---|---|
| ESO_ADD | |
| ESO_SUBTRACT | |
| ESO_ADD_ASSIGN | |
| ESO_SUBTRACT_ASSIGN | |
| ESO_MULTIPLY | |
| ESO_MULTIPLY_TRANSPOSE | |
| ESO_DIVIDE | |
| ESO_MODULO | |
| ESO_ASSIGN | |
| ESO_UNDEFINED | |
Definition at line 770 of file acado_types.hpp.
| enum ExportStruct |
| Enumerator | |
|---|---|
| ACADO_VARIABLES | |
| ACADO_WORKSPACE | |
| ACADO_PARAMS | |
| ACADO_VARS | |
| ACADO_LOCAL | |
| ACADO_ANY | |
| FORCES_PARAMS | |
| FORCES_OUTPUT | |
| FORCES_INFO | |
Definition at line 802 of file acado_types.hpp.
| enum ExportType |
| Enumerator | |
|---|---|
| INT | |
| REAL | |
| COMPLEX | |
| STATIC_CONST_INT | |
| STATIC_CONST_REAL | |
Definition at line 793 of file acado_types.hpp.
Summarises all possible ways of globablizing NLP steps.
| Enumerator | |
|---|---|
| GS_FULLSTEP | Full step. |
| GS_LINESEARCH | Linesearch. |
| GS_UNKNOWN | Unknown. |
Definition at line 221 of file acado_types.hpp.
Definition of several Hessian approximation modes.
| Enumerator | |
|---|---|
| CONSTANT_HESSIAN | |
| GAUSS_NEWTON | |
| FULL_BFGS_UPDATE | |
| BLOCK_BFGS_UPDATE | |
| GAUSS_NEWTON_WITH_BLOCK_BFGS | |
| EXACT_HESSIAN | |
| DEFAULT_HESSIAN_APPROXIMATION | |
Definition at line 611 of file acado_types.hpp.
Definition of several Hessian regularization modes.
| Enumerator | |
|---|---|
| BLOCK_REG | |
| CONDENSED_REG | |
Definition at line 626 of file acado_types.hpp.
Defines the mode of the exported implicit integrator.
Definition at line 158 of file acado_types.hpp.
| enum InfeasibleQPhandling |
Summarizes all available strategies for handling infeasible QPs within an SQP-type NLP solver.
Definition at line 658 of file acado_types.hpp.
| enum IntegratorType |
Summarizes all available integrators in standard ACADO.
| Enumerator | |
|---|---|
| INT_RK12 | Explicit Runge-Kutta integrator of order 1/2 |
| INT_RK23 | Explicit Runge-Kutta integrator of order 2/3 |
| INT_RK45 | Explicit Runge-Kutta integrator of order 4/5 |
| INT_RK78 | Explicit Runge-Kutta integrator of order 7/8 |
| INT_BDF | Implicit backward differentiation formula integrator. |
| INT_DISCRETE | Discrete time integrator |
| INT_LYAPUNOV45 | Explicit Runge-Kutta integrator of order 4/5 with Lyapunov structure exploiting |
| INT_UNKNOWN | unkown. |
Definition at line 256 of file acado_types.hpp.
| enum InterpolationMode |
Summarises all possible interpolation modes for VariablesGrids, Curves and the like.
Definition at line 230 of file acado_types.hpp.
| enum LinearAlgebraSolver |
Defines all possible linear algebra solvers.
| Enumerator | |
|---|---|
| HOUSEHOLDER_QR | |
| GAUSS_LU | |
| SIMPLIFIED_IRK_NEWTON | |
| SINGLE_IRK_NEWTON | |
| HOUSEHOLDER_METHOD | |
| SPARSE_LU | |
| LAS_UNKNOWN | |
Definition at line 145 of file acado_types.hpp.
| enum LogFrequency |
Defines logging frequency.
| Enumerator | |
|---|---|
| LOG_AT_START | |
| LOG_AT_END | |
| LOG_AT_EACH_ITERATION | |
Definition at line 313 of file acado_types.hpp.
| enum LogName |
Defines possible logging output
| Enumerator | |
|---|---|
| LOG_NOTHING | |
| LOG_NUM_NLP_ITERATIONS | Log number of NLP interations |
| LOG_NUM_SQP_ITERATIONS | Log number of SQP interations |
| LOG_NUM_QP_ITERATIONS | Log number of QP iterations |
| LOG_KKT_TOLERANCE | Log KKT tolerances |
| LOG_OBJECTIVE_VALUE | Log values objective function |
| LOG_MERIT_FUNCTION_VALUE | Log Merit function value |
| LOG_LINESEARCH_STEPLENGTH | Steplength of the line search routine (if used) |
| LOG_NORM_LAGRANGE_GRADIENT | Log norm of Lagrange gradient |
| LOG_IS_QP_RELAXED | Log whether the QP is relaxed or not |
| LOG_DUAL_RESIDUUM | |
| LOG_PRIMAL_RESIDUUM | |
| LOG_SURROGATE_DUALITY_GAP | |
| LOG_NUM_INTEGRATOR_STEPS | |
| LOG_TIME_SQP_ITERATION | |
| LOG_TIME_CONDENSING | |
| LOG_TIME_QP | |
| LOG_TIME_RELAXED_QP | |
| LOG_TIME_EXPAND | |
| LOG_TIME_EVALUATION | |
| LOG_TIME_HESSIAN_COMPUTATION | |
| LOG_TIME_GLOBALIZATION | |
| LOG_TIME_SENSITIVITIES | |
| LOG_TIME_LAGRANGE_GRADIENT | |
| LOG_TIME_PROCESS | |
| LOG_TIME_CONTROLLER | |
| LOG_TIME_ESTIMATOR | |
| LOG_TIME_CONTROL_LAW | |
| LOG_DIFFERENTIAL_STATES | Log all differential states in the order of occurrence |
| LOG_ALGEBRAIC_STATES | Log all algebraic states in the order of occurrence |
| LOG_PARAMETERS | Log all parameters in the order of occurrence |
| LOG_CONTROLS | Log all controls in the order of occurrence |
| LOG_DISTURBANCES | Log all disturbances in the order of occurrence |
| LOG_INTERMEDIATE_STATES | Log all intermediate states in the order of occurrence |
| LOG_DISCRETIZATION_INTERVALS | Log discretization intervals |
| LOG_STAGE_BREAK_POINTS | |
| LOG_FEEDBACK_CONTROL | |
| LOG_NOMINAL_CONTROLS | |
| LOG_NOMINAL_PARAMETERS | |
| LOG_SIMULATED_DIFFERENTIAL_STATES | |
| LOG_SIMULATED_ALGEBRAIC_STATES | |
| LOG_SIMULATED_CONTROLS | |
| LOG_SIMULATED_PARAMETERS | |
| LOG_SIMULATED_DISTURBANCES | |
| LOG_SIMULATED_INTERMEDIATE_STATES | |
| LOG_SIMULATED_OUTPUT | |
| LOG_PROCESS_OUTPUT | |
| LOG_NUMBER_OF_INTEGRATOR_STEPS | |
| LOG_NUMBER_OF_INTEGRATOR_REJECTED_STEPS | |
| LOG_NUMBER_OF_INTEGRATOR_FUNCTION_EVALUATIONS | |
| LOG_NUMBER_OF_BDF_INTEGRATOR_JACOBIAN_EVALUATIONS | |
| LOG_TIME_INTEGRATOR | |
| LOG_TIME_INTEGRATOR_FUNCTION_EVALUATIONS | |
| LOG_TIME_BDF_INTEGRATOR_JACOBIAN_EVALUATION | |
| LOG_TIME_BDF_INTEGRATOR_JACOBIAN_DECOMPOSITION | |
Definition at line 432 of file acado_types.hpp.
| enum LogPrintMode |
Defines all possibilities to print LogRecords.
Definition at line 323 of file acado_types.hpp.
| enum LogRecordItemType |
| Enumerator | |
|---|---|
| LRT_ENUM | |
| LRT_VARIABLE | |
| LRT_UNKNOWN | |
Definition at line 303 of file acado_types.hpp.
| enum MeasurementGrid |
The available options for providing the grid of measurements.
| Enumerator | |
|---|---|
| OFFLINE_GRID | An equidistant grid specified independent of the integration grid. |
| ONLINE_GRID | A random grid, provided online by the user. |
Definition at line 271 of file acado_types.hpp.
| enum MergeMethod |
Defines all possible methods of merging variables grids in case a grid point exists in both grids.
| Enumerator | |
|---|---|
| MM_KEEP | Keeps original values. |
| MM_REPLACE | Replace by new values. |
| MM_DUPLICATE | Duplicate grid point (i.e. keeping old and adding new). |
Definition at line 116 of file acado_types.hpp.
| enum MonotonicityType |
Defines all possible monotonicity types.
| Enumerator | |
|---|---|
| MT_CONSTANT | |
| MT_NONDECREASING | |
| MT_NONINCREASING | |
| MT_NONMONOTONIC | |
| MT_UNKNOWN | |
Definition at line 168 of file acado_types.hpp.
| enum NeutralElement |
Defines the Neutral Elements ZERO and ONE as well as the default NEITHER_ONE_NOR_ZERO
| Enumerator | |
|---|---|
| NE_ZERO | |
| NE_ONE | |
| NE_NEITHER_ONE_NOR_ZERO | |
Definition at line 64 of file acado_types.hpp.
| enum OperatingSystem |
| Enumerator | |
|---|---|
| OS_DEFAULT | |
| OS_UNIX | |
| OS_WINDOWS | |
Definition at line 785 of file acado_types.hpp.
| enum OperatorName |
Defines the names of all implemented symbolic operators.
Definition at line 72 of file acado_types.hpp.
| enum OptionsName |
Definition at line 331 of file acado_types.hpp.
Defines the pareto front generation options.
Definition at line 739 of file acado_types.hpp.
| enum PlotFormat |
Defines all possible plot formats.
| Enumerator | |
|---|---|
| PF_PLAIN | Plot with linear x- and y-axes. |
| PF_LOG | Plot with linear x-axis and logarithmic y-axis. |
| PF_LOG_LOG | Plot with logarithmic x- and y-axes. |
| PF_UNKNOWN | Plot format unknown. |
Definition at line 535 of file acado_types.hpp.
| enum PlotFrequency |
| Enumerator | |
|---|---|
| PLOT_AT_START | |
| PLOT_AT_END | |
| PLOT_AT_EACH_ITERATION | |
| PLOT_IN_ANY_CASE | |
| PLOT_NEVER | |
Definition at line 498 of file acado_types.hpp.
| enum PlotMode |
Defines all possible plot modes.
| Enumerator | |
|---|---|
| PM_LINES | Plot data points linearly interpolated with lines. |
| PM_POINTS | Plot data points as single points. |
| PM_UNKNOWN | Plot mode unknown. |
Definition at line 547 of file acado_types.hpp.
| enum PlotName |
| Enumerator | |
|---|---|
| PLOT_NOTHING | |
| PLOT_KKT_TOLERANCE | |
| PLOT_OBJECTIVE_VALUE | |
| PLOT_MERIT_FUNCTION_VALUE | |
| PLOT_LINESEARCH_STEPLENGTH | |
| PLOT_NORM_LAGRANGE_GRADIENT | |
Definition at line 508 of file acado_types.hpp.
| enum PrintLevel |
Summarises all possible print levels. Print levels are used to describe the desired amount of output during runtime of ACADO Toolkit.
Definition at line 292 of file acado_types.hpp.
| enum PrintScheme |
Defines possible printing types used in logging.
Definition at line 574 of file acado_types.hpp.
| enum ProcessPlotName |
| Enumerator | |
|---|---|
| PLOT_NOMINAL | |
| PLOT_REAL | |
Definition at line 526 of file acado_types.hpp.
Summarizes all possible algorithms for simulating the process.
| Enumerator | |
|---|---|
| SIMULATION_BY_INTEGRATION | Simulation by using an integrator. |
| SIMULATION_BY_COLLOCATION | Simulation by using a collocation scheme. |
Definition at line 602 of file acado_types.hpp.
| enum QPSolverName |
| Enumerator | |
|---|---|
| QP_QPOASES | |
| QP_QPOASES3 | |
| QP_FORCES | |
| QP_QPDUNES | |
| QP_HPMPC | |
| QP_GENERIC | |
| QP_NONE | |
Definition at line 633 of file acado_types.hpp.
| enum QPStatus |
Summarizes all possible states of a QP problem.
Definition at line 669 of file acado_types.hpp.
| enum returnValueLevel |
Defines the importance level of the message
Definition at line 1120 of file acado_types.hpp.
| enum SensitivityType |
Summarizes all possible sensitivity types
Definition at line 584 of file acado_types.hpp.
Defines .
| Enumerator | |
|---|---|
| SPARSE_SOLVER | |
| CONDENSING | |
| FULL_CONDENSING | |
| FULL_CONDENSING_N2 | |
| CONDENSING_N2 | |
| BLOCK_CONDENSING_N2 | |
| FULL_CONDENSING_N2_FACTORIZATION | |
Definition at line 755 of file acado_types.hpp.
Summarises all possible ways of discretising the system's states.
Definition at line 200 of file acado_types.hpp.
| enum StateOfAggregation |
Summarizes all possible states of aggregation. (e.g. a mesh for an integration routine can be freezed, unfreezed, etc.)
Definition at line 243 of file acado_types.hpp.
| enum SubBlockMatrixType |
Defines all possible sub-block matrix types.
| Enumerator | |
|---|---|
| SBMT_ZERO | |
| SBMT_ONE | |
| SBMT_DENSE | |
| SBMT_UNKNOWN | |
Definition at line 126 of file acado_types.hpp.
| enum SubPlotType |
Defines all possible sub-plot types.
| Enumerator | |
|---|---|
| SPT_VARIABLE | |
| SPT_VARIABLE_VARIABLE | |
| SPT_VARIABLE_EXPRESSION | |
| SPT_VARIABLES_GRID | |
| SPT_EXPRESSION | |
| SPT_EXPRESSION_EXPRESSION | |
| SPT_EXPRESSION_VARIABLE | |
| SPT_ENUM | |
| SPT_UNKNOWN | |
Definition at line 558 of file acado_types.hpp.
| enum TimeHorizonElement |
Defines the time horizon start and end.
| Enumerator | |
|---|---|
| AT_TRANSITION | |
| AT_START | |
| AT_END | |
Definition at line 729 of file acado_types.hpp.
| enum UnrollOption |
Unrolling option.
| Enumerator | |
|---|---|
| UNROLL | |
| NO_UNROLL | |
| HEURISTIC_UNROLL | |
Definition at line 280 of file acado_types.hpp.
| enum VariableType |
Defines the names of all implemented variable types.
Definition at line 95 of file acado_types.hpp.
| BEGIN_NAMESPACE_ACADO typedef unsigned int uint |
Short-cut for unsigned integer.
Definition at line 42 of file acado_types.hpp.