Classes | |
class | Acos |
Implements the scalar inverse cosine operator (arccos) within the symbolic operators family. More... | |
class | Addition |
Implements the scalar addition operator within the symbolic expressions family. More... | |
class | AlgebraicConsistencyConstraint |
Deals with algebraic consistency constraints within optimal control problems. More... | |
class | Asin |
Implements the scalar inverse sine operator (arcsin) within the symbolic operators family. More... | |
class | Atan |
Implements the scalar inverse tangens operator (arctan) within the symbolic operators family. More... | |
class | BandedCP |
Data class for storing conic programs arising from optimal control. More... | |
class | BinaryOperator |
Abstract base class for all scalar-valued binary operators within the symbolic operators family. More... | |
class | BlockMatrix |
Implements a very rudimentary block sparse matrix class. More... | |
class | BoundaryConstraint |
Stores and evaluates boundary constraints within optimal control problems. More... | |
class | BoxConstraint |
Stores and evaluates box constraints within optimal control problems. More... | |
class | CFunction |
(no description yet) More... | |
class | Clock |
Base class for all kind of time measurements. More... | |
class | ColoredNoise |
Generates pseudo-random colored noise for simulating the Process. More... | |
class | Constraint |
Stores and evaluates the constraints of optimal control problems. More... | |
class | ConstraintElement |
Base class for all kind of constraints (except for bounds) within optimal control problems. More... | |
class | COperator |
The class COperator is an auxiliary class to use C-Functions within a function evaluation tree. More... | |
class | Cos |
Implements the scalar cosine operator within the symbolic operators family. More... | |
class | CoupledPathConstraint |
Stores and evaluates coupled path constraints within optimal control problems. More... | |
class | Curve |
Allows to work with piecewise-continous function defined over a scalar time interval. More... | |
class | DenseCP |
Data class for storing generic conic programs. More... | |
class | DifferentialEquation |
Allows to setup and evaluate differential equations (ODEs and DAEs) based on SymbolicExpressions. More... | |
class | DiscretizedDifferentialEquation |
Allows to setup and evaluate discretized differential equations based on SymbolicExpressions. More... | |
class | DoubleConstant |
Implements a scalar constant within the symbolic operators family. More... | |
class | EvaluationBase |
Abstract base class for templated evaluation of operators. More... | |
class | EvaluationPoint |
Allows to setup function evaluation points. More... | |
class | EvaluationTemplate< T > |
Templated class for operator evaluation. More... | |
class | Exp |
Implements the scalar exponential operator within the symbolic operators family. More... | |
class | Expression |
Base class for all variables within the symbolic expressions family. More... | |
class | Function |
Allows to setup and evaluate a general function based on SymbolicExpressions. More... | |
class | FunctionEvaluationTree |
Organizes the evaluation of the function tree. More... | |
class | GaussianNoise |
Generates pseudo-random Gaussian noise for simulating the Process. More... | |
class | Grid |
Allows to conveniently handle (one-dimensional) grids consisting of time points. More... | |
class | Interval |
Implements a rudimentary interval class. More... | |
class | LagrangeTerm |
Stores and evaluates Lagrange terms within optimal control problems. More... | |
class | Logarithm |
Implements the scalar logarithm operator within the symbolic operators family. More... | |
class | Logger |
A very simple logging class. More... | |
class | LSQEndTerm |
Stores and evaluates LSQ mayer terms within optimal control problems. More... | |
class | LSQTerm |
Stores and evaluates LSQ terms within optimal control problems. More... | |
class | Lyapunov |
Implements a parameter. More... | |
class | MatrixVariable |
Provides matrix-valued optimization variables. More... | |
class | MatrixVariablesGrid |
Provides a time grid consisting of matrix-valued optimization variables at each grid point. More... | |
class | MayerTerm |
Stores and evaluates Mayer terms within optimal control problems. More... | |
class | ModelContainer |
Container class to store and pass data to the ModelData class. More... | |
class | ModelData |
Data class for defining models and everything that is related, to be passed to the integrator. More... | |
class | NLP |
Data class for defining static optimization problems. More... | |
class | Noise |
Base class for generating pseudo-random noise for simulating the Process. More... | |
class | NonsmoothOperator |
Abstract base class for all scalar-valued symbolic operators. More... | |
class | Objective |
Stores and evaluates the objective function of optimal control problems. More... | |
class | ObjectiveElement |
Base class for all kind of objective function terms within optimal control problems. More... | |
class | OCP |
Data class for defining optimal control problems. More... | |
class | OCPiterate |
Data class for storing generic optimization variables. More... | |
class | Operator |
Abstract base class for all scalar-valued symbolic operators. More... | |
class | OutputFcn |
Allows to setup and evaluate output functions based on SymbolicExpressions. More... | |
class | PathConstraint |
Stores and evaluates path constraints within optimal control problems. More... | |
class | PointConstraint |
Stores and evaluates pointwise constraints within optimal control problems. More... | |
class | Power |
Implements the scalar power operator within the symbolic operators family. More... | |
class | Power_Int |
Implements the scalar power operator with integer exponent within the symbolic operators family. More... | |
class | Product |
Implements the scalar product operator within the symbolic operators family. More... | |
class | Projection |
Implements the projection operator within the symbolic operators family. More... | |
class | Quotient |
Implements the scalar quotient operator within the symbolic operators family. More... | |
class | RealClock |
Allows real time measurements based on the system's clock. More... | |
class | returnValue |
Allows to pass back messages to the calling function. More... | |
struct | ReturnValueList |
Data structure for entries in returnValueList. More... | |
class | SimulationClock |
Simulates real time measurements for simulations. More... | |
class | Sin |
Implements the scalar sine operator within the symbolic operators family. More... | |
class | SmoothOperator |
Abstract base class for all scalar-valued symbolic operators. More... | |
class | Subtraction |
Implements the scalar subtraction operator within the symbolic operators family. More... | |
class | SymbolicIndexList |
Manages the indices of SymbolicVariables. More... | |
class | Tan |
Implements the scalar tangens operator within the symbolic operators family. More... | |
class | TevaluationPoint< T > |
Allows to setup function evaluation points. More... | |
class | Tmatrix< T > |
Implements a templated dense matrix class. More... | |
class | Transition |
Allows to setup and evaluate transition functions based on SymbolicExpressions. More... | |
class | TreeProjection |
Implements the tree-projection operator within the family of SymbolicOperators. More... | |
class | UnaryOperator |
Abstract base class for all scalar-valued unary operators within the symbolic operators family. More... | |
class | UniformNoise |
Generates pseudo-random uniformly distributed noise for simulating the Process. More... | |
class | VariableSettings |
Provides variable-specific settings for vector- or matrix-valued optimization variables (for internal use). More... | |
class | VariablesGrid |
Provides a time grid consisting of vector-valued optimization variables at each grid point. More... | |
enum returnValueType |
Defines all symbols for global return values.
The enumeration returnValueType defines all symbols for global return values. Important: All return values are assumed to be nonnegative!
Enumerator | |
---|---|
TERMINAL_LIST_ELEMENT | Terminal list element, internal usage only! |
SUCCESSFUL_RETURN | Successful return. |
RET_DIV_BY_ZERO | Division by zero. |
RET_INDEX_OUT_OF_BOUNDS | Index out of bounds. |
RET_INVALID_ARGUMENTS | At least one of the arguments is invalid. |
RET_ERROR_UNDEFINED | Error number undefined. |
RET_WARNING_UNDEFINED | Warning number undefined. |
RET_INFO_UNDEFINED | Info number undefined. |
RET_EWI_UNDEFINED | Error/warning/info number undefined. |
RET_AVAILABLE_WITH_LINUX_ONLY | This function is available under Linux only. |
RET_UNKNOWN_BUG | The error occured is not yet known. |
RET_PRINTLEVEL_CHANGED | Print level changed. |
RET_NOT_YET_IMPLEMENTED | Requested function is not yet implemented. |
RET_NOT_IMPLEMENTED_YET | Requested function is not yet implemented. |
RET_NOT_IMPLEMENTED_IN_BASE_CLASS | Requested function is not implemented within this class. |
RET_ASSERTION | An assertion has been violated. |
RET_MEMBER_NOT_INITIALISED | Requested member has not been initialised. |
RET_ABSTRACT_BASE_CLASS | Invalid call to member function of abstract base class. |
RET_NO_DATA_FOUND | There has no data been found. |
RET_INPUT_DIMENSION_MISMATCH | The dimensions of the input are wrong. |
RET_STRING_EXCEEDS_LENGTH | String exceeds maximum length. |
RET_FILE_NOT_FOUND | The file has not been found. |
RET_FILE_CAN_NOT_BE_OPENED | The file can not be opened. |
RET_CAN_NOT_WRITE_INTO_FILE | The routine has no write access or writing into the file failed. |
RET_FILE_CAN_NOT_BE_CLOSED | The file could not be closed. |
RET_FILE_HAS_NO_VALID_ENTRIES | The file has no valid entries. |
RET_DOES_DIRECTORY_EXISTS | Could not open file, check if given directory exists. |
RET_VECTOR_DIMENSION_MISMATCH | Incompatible vector dimensions. |
RET_DIFFERENTIAL_STATE_DIMENSION_MISMATCH | Incompatible differential state vector dimensions. |
RET_ALGEBRAIC_STATE_DIMENSION_MISMATCH | Incompatible algebraic state vector dimensions. |
RET_CONTROL_DIMENSION_MISMATCH | Incompatible control vector dimensions. |
RET_PARAMETER_DIMENSION_MISMATCH | Incompatible parameter vector dimensions. |
RET_DISTURBANCE_DIMENSION_MISMATCH | Incompatible disturbance vector dimensions. |
RET_OUTPUT_DIMENSION_MISMATCH | Incompatible output vector dimensions. |
RET_MATRIX_NOT_SQUARE | Operation requires square matrix. |
RET_LINEAR_SYSTEM_NUMERICALLY_SINGULAR | Linear system could not be solved with required accuracy. Check whether the system is singular or ill-conditioned. |
RET_GRIDPOINT_SETUP_FAILED | Failed to setup grid point. |
RET_GRIDPOINT_HAS_INVALID_TIME | Unable to setup a grid point with this time. |
RET_CONFLICTING_GRIDS | Conflicting grids detected. |
RET_TIME_INTERVAL_NOT_VALID | The time interval is not valid / not in range. |
RET_INVALID_TIME_POINT | A time point is not in its permissible range. |
RET_OPTION_ALREADY_EXISTS | An option with this name already exists. |
RET_OPTION_DOESNT_EXIST | An option with this name does not exist. |
RET_OPTIONS_LIST_CORRUPTED | Internal options list is corrupted. |
RET_INVALID_OPTION | A user-defined option has an invalid value. |
RET_PLOTTING_FAILED | Unable to plot current window. |
RET_EMPTY_PLOT_DATA | Unable to plot subplot as plot data is empty. |
RET_PLOT_WINDOW_CORRUPTED | PlotWindow has corrupted list of subplots. |
RET_PLOT_COLLECTION_CORRUPTED | PlotCollection has corrupted list of plot windows. |
RET_LOG_RECORD_CORRUPTED | LogRecord has corrupted list of items. |
RET_LOG_ENTRY_DOESNT_EXIST | An log entry with this name does not exist. |
RET_LOG_COLLECTION_CORRUPTED | LogCollection has corrupted list of records. |
RET_BLOCK_DIMENSION_MISMATCH | Blocks with incompatible dimensions. |
RET_NO_PROCESS_SPECIFIED | No process has been specified. |
RET_NO_CONTROLLER_SPECIFIED | No controller has been specified. |
RET_ENVIRONMENT_INIT_FAILED | Unable to initialize simulation environment. |
RET_ENVIRONMENT_STEP_FAILED | Unable to perform simulation environment step. |
RET_COMPUTATIONAL_DELAY_TOO_BIG | Simulation stops as computational delay is too big. |
RET_COMPUTATIONAL_DELAY_NOT_SUPPORTED | Simulation of computational delay is not yet supported. |
RET_BLOCK_NOT_READY | Block is not ready. |
RET_NO_SYSTEM_TIME | No system time available. |
RET_CLOCK_NOT_READY | Unable to start the clock as it is not ready. |
RET_PROCESS_INIT_FAILED | Unable to initialize process. |
RET_PROCESS_STEP_FAILED | Unable to perform process step. |
RET_PROCESS_STEP_FAILED_DISTURBANCE | Unable to perform process step due to error in disturbance evaluation. |
RET_PROCESS_RUN_FAILED | Unable to run process simulation. |
RET_NO_DYNAMICSYSTEM_SPECIFIED | No dynamic system has been specified. |
RET_NO_INTEGRATIONALGORITHM_SPECIFIED | No integration algorithm has been specified. |
RET_NO_DISCRETE_TIME_SYSTEMS_SUPPORTED | Discrete-time systems are not yet supported. |
RET_WRONG_DISTURBANCE_HORIZON | Process disturbance is defined over an incompatible time horizon. |
RET_ACTUATOR_INIT_FAILED | Unable to initialize actuator. |
RET_ACTUATOR_STEP_FAILED | Unable to perform actuator step. |
RET_SENSOR_INIT_FAILED | Unable to initialize sensor. |
RET_SENSOR_STEP_FAILED | Unable to perform sensor step. |
RET_GENERATING_NOISE_FAILED | Unable to generate noise. |
RET_DELAYING_INPUTS_FAILED | Unable to delay inputs. |
RET_DELAYING_OUTPUTS_FAILED | Unable to delay outputs. |
RET_INCOMPATIBLE_ACTUATOR_SAMPLING_TIME | Actuator sampling time has to be an integer multiple of dynamic system sample time. |
RET_INCOMPATIBLE_SENSOR_SAMPLING_TIME | Sensor sampling time has to be an integer multiple of dynamic system sample time. |
RET_NO_DIFFERENT_NOISE_SAMPLING_FOR_DISCRETE | When using discrete-time systems, noise has to be sampled equally for all components. |
RET_NO_NOISE_GENERATED | No noise has been generated. |
RET_NO_NOISE_SETTINGS | No noise settings has been defined. |
RET_INVALID_NOISE_SETTINGS | Specified noise settings are invalid. |
RET_CONTROLLER_INIT_FAILED | Unable to initialize controller. |
RET_CONTROLLER_STEP_FAILED | Unable to perform controller step. |
RET_NO_ESTIMATOR_SPECIFIED | No estimator has been specified. |
RET_NO_CONTROLLAW_SPECIFIED | No control law has been specified. |
RET_NO_REALTIME_MODE_AVAILABLE | Control law does not support real-time mode. |
RET_DCU_INIT_FAILED | Unable to initialize dynamic control unit. |
RET_DCU_STEP_FAILED | Unable to perform step of dynamic control unit. |
RET_ESTIMATOR_INIT_FAILED | Unable to initialize estimator. |
RET_ESTIMATOR_STEP_FAILED | Unable to perform estimator step. |
RET_OPTIMIZER_INIT_FAILED | Unable to initialize optimizer. |
RET_OPTIMIZER_STEP_FAILED | Unable to perform optimizer step. |
RET_NO_OCP_SPECIFIED | No optimal control problem has been specified. |
RET_NO_SOLUTIONALGORITHM_SPECIFIED | No solution algorithm has been specified. |
RET_CONTROLLAW_INIT_FAILED | Unable to initialize feedback law. |
RET_CONTROLLAW_STEP_FAILED | Unable to perform feedback law step. |
RET_NO_OPTIMIZER_SPECIFIED | No optimizer has been specified. |
RET_INVALID_PID_OUTPUT_DIMENSION | Invalid output dimension of PID controller, reset to 1. |
RET_IMMEDIATE_FEEDBACK_ONE_ITERATION | Resetting maximum number of iterations to 1 as required for using immediate feedback. |
RET_OUTPUTTRANSFORMATOR_INIT_FAILED | Unable to initialize output transformator. |
RET_OUTPUTTRANSFORMATOR_STEP_FAILED | Unable to perform output transformator step. |
RET_INVALID_USE_OF_FUNCTION | Invalid use of the class function. |
RET_INFEASIBLE_CONSTRAINT | Infeasible Constraints detected. |
RET_ONLY_SUPPORTED_FOR_SYMBOLIC_FUNCTIONS | This routine is for symbolic functions only. |
RET_INFEASIBLE_ALGEBRAIC_CONSTRAINT | Infeasible algebraic constraints are not allowed and will be ignored. |
RET_ILLFORMED_ODE | ODE needs to depend on all differential states. |
RET_PRECISION_OUT_OF_RANGE | the requested precision is out of range. |
RET_ERROR_WHILE_PRINTING_A_FILE | An error has occured while printing a file. |
RET_INDEX_OUT_OF_RANGE | An index was not in the range. |
RET_INTERMEDIATE_STATE_HAS_NO_ARGUMENT | The intermediate state has no argument. |
RET_DIMENSION_NOT_SPECIFIED | The dimension of a array was not specified. |
RET_DDQ_DIMENSION_MISMATCH | ddq argument must be of size 3x1 |
RET_CAN_ONLY_SOLVE_2ND_ORDER_KINVECS | can only solve 2nd order KinVecs |
RET_GAUSS_NEWTON_APPROXIMATION_NOT_SUPPORTED | The objective does not support Gauss-Newton Hessian approximations. |
RET_REFERENCE_SHIFTING_WORKS_FOR_LSQ_TERMS_ONLY | The reference shifting works only for LSQ objectives. |
RET_TRIVIAL_RHS | the dimension of the rhs is zero. |
RET_MISSING_INPUTS | the integration routine misses some inputs. |
RET_TO_SMALL_OR_NEGATIVE_TIME_INTERVAL | the time interval was too small or negative. |
RET_FINAL_STEP_NOT_PERFORMED_YET | the integration routine is not ready. |
RET_ALREADY_FROZEN | the integrator is already freezing or frozen. |
RET_MAX_NUMBER_OF_STEPS_EXCEEDED | the maximum number of steps has been exceeded. |
RET_WRONG_DEFINITION_OF_SEEDS | the seeds are not set correctly or in the wrong order. |
RET_NOT_FROZEN | the mesh is not frozen and/or forward results not stored. |
RET_TO_MANY_DIFFERENTIAL_STATES | there are to many differential states. |
RET_TO_MANY_DIFFERENTIAL_STATE_DERIVATIVES | there are to many diff. state derivatives. |
RET_RK45_CAN_NOT_TREAT_DAE | An explicit Runge-Kutta solver cannot treat DAEs. |
RET_CANNOT_TREAT_DAE | The algorithm cannot treat DAEs. |
RET_INPUT_HAS_WRONG_DIMENSION | At least one of the inputs has a wrong dimension. |
RET_INPUT_OUT_OF_RANGE | One of the inputs is out of range. |
RET_THE_DAE_INDEX_IS_TOO_LARGE | The index of the DAE is larger than 1. |
RET_UNSUCCESSFUL_RETURN_FROM_INTEGRATOR_RK45 | the integration routine stopped due to a problem during the function evaluation. |
RET_UNSUCCESSFUL_RETURN_FROM_INTEGRATOR_BDF | the integration routine stopped as the required accuracy can not be obtained. |
RET_CANNOT_TREAT_DISCRETE_DE | This integrator cannot treat discrete-time differential equations. |
RET_CANNOT_TREAT_CONTINUOUS_DE | This integrator cannot treat time-continuous differential equations. |
RET_CANNOT_TREAT_IMPLICIT_DE | This integrator cannot treat differential equations in implicit form. |
RET_CANNOT_TREAT_EXPLICIT_DE | This integrator cannot treat differential equations in explicit form. |
RET_TO_MANY_DIFFERENTIAL_EQUATIONS | The number of differential equations is too large. |
RET_BREAK_POINT_SETUP_FAILED | The break point setup failed. |
RET_WRONG_DEFINITION_OF_STAGE_TRANSITIONS | The definition of stage transitions is wrong. |
RET_TRANSITION_DEPENDS_ON_ALGEBRAIC_STATES | A transition should never depend on algebraic states. |
RET_NO_VALID_OBJECTIVE | No valid objective found. |
RET_INCONSISTENT_BOUNDS | The bounds are inconsistent. |
RET_INCOMPATIBLE_DIMENSIONS | Incopatible dimensions detected. |
RET_GRID_SETUP_FAILED | Discretization of the OCP failed. |
RET_OPTALG_INIT_FAILED | Initialization of optimization algorithm failed. |
RET_OPTALG_STEP_FAILED | Step of optimization algorithm failed. |
RET_OPTALG_FEEDBACK_FAILED | Feedback step of optimization algorithm failed. |
RET_OPTALG_PREPARE_FAILED | Preparation step of optimization algorithm failed. |
RET_OPTALG_SOLVE_FAILED | Problem could not be solved with given optimization algorithm. |
RET_REALTIME_NO_INITIAL_VALUE | No initial value has been specified. |
RET_INTALG_INIT_FAILED | Initialization of integration algorithm failed. |
RET_INTALG_INTEGRATION_FAILED | Integration algorithm failed to integrate dynamic system. |
RET_INTALG_NOT_READY | Integration algorithm has not been initialized. |
RET_PLOT_WINDOW_CAN_NOT_BE_OPEN | ACADO was not able to open the plot window. |
CONVERGENCE_ACHIEVED | convergence achieved. |
CONVERGENCE_NOT_YET_ACHIEVED | convergence not yet achieved. |
RET_NLP_INIT_FAILED | Initialization of NLP solver failed. |
RET_NLP_STEP_FAILED | Step of NLP solver failed. |
RET_NLP_SOLUTION_FAILED | NLP solution failed. |
RET_INITIALIZE_FIRST | Object needs to be initialized first. |
RET_SOLVER_NOT_SUTIABLE_FOR_REAL_TIME_MODE | The specified NLP solver is not designed for a real-time mode. |
RET_ILLFORMED_HESSIAN_MATRIX | Hessian matrix is too ill-conditioned to continue. |
RET_NONSYMMETRIC_HESSIAN_MATRIX | Hessian matrix is not symmetric, proceeding with symmetrized Hessian. |
RET_UNABLE_TO_EVALUATE_OBJECTIVE | Evaluation of objective function failed. |
RET_UNABLE_TO_EVALUATE_CONSTRAINTS | Evaluation of constraints failed. |
RET_UNABLE_TO_INTEGRATE_SYSTEM | Integration of dynamic system failed. Try to adjust integrator tolerances using set( ABSOLUTE_TOLERANCE,<double> ) and set( INTEGRATOR_TOLERANCE,<double> ). |
RET_NEED_TO_ACTIVATE_RTI | Feedback step requires real-time iterations to be activated. Use set( USE_REALTIME_ITERATIONS,YES ) to do so. |
RET_CONIC_PROGRAM_INFEASIBLE | The optimization problem is infeasible. |
RET_CONIC_PROGRAM_SOLUTION_FAILED | Conic Program solution failed. The optimization problem might be infeasible. |
RET_CONIC_PROGRAM_NOT_SOLVED | The Conic Program has not been solved successfully. |
RET_UNABLE_TO_CONDENSE | Unable to condense banded CP. |
RET_UNABLE_TO_EXPAND | Unable to expand condensed CP. |
RET_NEED_TO_CONDENSE_FIRST | Condensing cannot be frozen as banded CP needs to be condensed first. |
RET_BANDED_CP_INIT_FAILED | Initialization of banded CP solver failed. |
RET_BANDED_CP_SOLUTION_FAILED | Solution of banded CP failed. |
RET_TRANSITION_NOT_DEFINED | |
RET_QP_INIT_FAILED |
QP initialization failed. |
RET_QP_SOLUTION_FAILED | QP solution failed. |
RET_QP_SOLUTION_REACHED_LIMIT | QP solution stopped as iteration limit is reached. |
RET_QP_INFEASIBLE | QP solution failed due to infeasibility. |
RET_QP_UNBOUNDED | QP solution failed due to unboundedness. |
RET_QP_NOT_SOLVED | QP has not been solved. |
RET_RELAXING_QP | QP needs to be relaxed due to infeasibility. |
RET_COULD_NOT_RELAX_QP | QP could not be relaxed. |
RET_QP_SOLVER_CAN_ONLY_SOLVE_QP | The QP solver can not deal with general conic problems. |
RET_QP_HAS_INCONSISTENT_BOUNDS | QP cannot be solved due to inconsistent bounds. |
RET_UNABLE_TO_HOTSTART_QP | Unable to hotstart QP with given solver. |
RET_NONPOSITIVE_WEIGHT | Weighting matrices must be positive semi-definite. |
RET_INITIAL_CHOLESKY_FAILED | Setting up initial Cholesky decompostion failed. |
RET_HOMOTOPY_STEP_FAILED | Unable to perform homotopy step. |
RET_STEPDIRECTION_DETERMINATION_FAILED | Determination of step direction failed. |
RET_STEPDIRECTION_FAILED_CHOLESKY | Abnormal termination due to Cholesky factorisation. |
RET_STEPLENGTH_DETERMINATION_FAILED | Determination of step direction failed. |
RET_OPTIMAL_SOLUTION_FOUND | Optimal solution of neighbouring QP found. |
RET_MAX_NWSR_REACHED | Maximum number of working set recalculations performed. |
RET_MATRIX_NOT_SPD | DMatrix is not positive definite. |
RET_CODE_EXPORT_SUCCESSFUL | Code generation successful. |
RET_UNABLE_TO_EXPORT_CODE | Unable to generate code. |
RET_INVALID_OBJECTIVE_FOR_CODE_EXPORT | Only standard LSQ objective supported for code generation. |
RET_NO_DISCRETE_ODE_FOR_CODE_EXPORT | No discrete-time ODEs supported for code generation. |
RET_ONLY_ODE_FOR_CODE_EXPORT | Only ODEs supported for code generation. |
RET_ONLY_STATES_AND_CONTROLS_FOR_CODE_EXPORT | No parameters, disturbances or algebraic states supported for code generation. |
RET_ONLY_EQUIDISTANT_GRID_FOR_CODE_EXPORT | Only equidistant evaluation grids supported for code generation. |
RET_ONLY_BOUNDS_FOR_CODE_EXPORT | Only state and control bounds supported for code generation. |
RET_QPOASES_EMBEDDED_NOT_FOUND | Embedded qpOASES code not found. |
RET_UNABLE_TO_EXPORT_STATEMENT | Unable to export statement due to incomplete definition. |
RET_INVALID_CALL_TO_EXPORTED_FUNCTION | Invalid call to export functions (check number of calling arguments). |
RET_INVALID_LINEAR_OUTPUT_FUNCTION | Invalid definition of the nonlinear function in a linear output system. |
Definition at line 832 of file acado_types.hpp.