acado_message_handling.cpp
Go to the documentation of this file.
1 /*
2  * This file is part of ACADO Toolkit.
3  *
4  * ACADO Toolkit -- A Toolkit for Automatic Control and Dynamic Optimization.
5  * Copyright (C) 2008-2014 by Boris Houska, Hans Joachim Ferreau,
6  * Milan Vukov, Rien Quirynen, KU Leuven.
7  * Developed within the Optimization in Engineering Center (OPTEC)
8  * under supervision of Moritz Diehl. All rights reserved.
9  *
10  * ACADO Toolkit is free software; you can redistribute it and/or
11  * modify it under the terms of the GNU Lesser General Public
12  * License as published by the Free Software Foundation; either
13  * version 3 of the License, or (at your option) any later version.
14  *
15  * ACADO Toolkit is distributed in the hope that it will be useful,
16  * but WITHOUT ANY WARRANTY; without even the implied warranty of
17  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
18  * Lesser General Public License for more details.
19  *
20  * You should have received a copy of the GNU Lesser General Public
21  * License along with ACADO Toolkit; if not, write to the Free Software
22  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
23  *
24  */
25 
26 
33 #include <string.h>
34 
35 
38 
39 using namespace std;
40 
42 
52 typedef struct {
54  const char* data;
58 
68 {
69 /* miscellaneous */
70 { SUCCESSFUL_RETURN, "Successful return", VS_VISIBLE },
71 { RET_DIV_BY_ZERO, "Division by zero", VS_VISIBLE },
72 { RET_INDEX_OUT_OF_BOUNDS, "Index out of bounds", VS_VISIBLE },
73 { RET_INVALID_ARGUMENTS, "At least one of the arguments is invalid", VS_VISIBLE },
74 { RET_ERROR_UNDEFINED, "Error number undefined", VS_VISIBLE },
75 { RET_WARNING_UNDEFINED, "Warning number undefined", VS_VISIBLE },
76 { RET_INFO_UNDEFINED, "Info number undefined", VS_VISIBLE },
77 { RET_EWI_UNDEFINED, "Error/warning/info number undefined", VS_VISIBLE },
78 { RET_AVAILABLE_WITH_LINUX_ONLY, "This function is available under Linux only", VS_HIDDEN },
79 { RET_UNKNOWN_BUG, "The error occured is not yet known", VS_VISIBLE },
80 { RET_PRINTLEVEL_CHANGED, "Print level changed", VS_VISIBLE },
81 { RET_NOT_YET_IMPLEMENTED, "Requested function is not yet implemented", VS_VISIBLE },
82 { RET_NOT_IMPLEMENTED_YET, "Requested function is not yet implemented", VS_VISIBLE },
83 { RET_NOT_IMPLEMENTED_IN_BASE_CLASS, "Requested function is not implemented within this class", VS_VISIBLE },
84 { RET_ASSERTION, "An assertion has been violated", VS_VISIBLE },
85 { RET_MEMBER_NOT_INITIALISED, "Requested member has not been initialised", VS_VISIBLE },
86 { RET_ABSTRACT_BASE_CLASS, "Invalid call to member function of abstract base class", VS_VISIBLE },
87 { RET_NO_DATA_FOUND, "There has no data been found", VS_VISIBLE },
88 { RET_INPUT_DIMENSION_MISMATCH, "The dimensions of the input are wrong", VS_VISIBLE },
89 { RET_STRING_EXCEEDS_LENGTH, "String exceeds maximum length", VS_VISIBLE },
90 
91 /* IO utils: */
92 { RET_FILE_NOT_FOUND, "The file has not been found", VS_VISIBLE },
93 { RET_FILE_CAN_NOT_BE_OPENED, "The file can not be opened", VS_VISIBLE },
94 { RET_CAN_NOT_WRITE_INTO_FILE, "The routine has no write access or writing into the file failed", VS_VISIBLE },
95 { RET_FILE_CAN_NOT_BE_CLOSED, "The file could not be closed", VS_VISIBLE },
96 { RET_FILE_HAS_NO_VALID_ENTRIES, "The file has no valid entries", VS_VISIBLE },
97 { RET_DOES_DIRECTORY_EXISTS, "Could not open file, check if given directory exists", VS_VISIBLE },
98 
99 /* DMatrix/DVector */
100 { RET_VECTOR_DIMENSION_MISMATCH, "Incompatible vector dimensions", VS_VISIBLE },
101 { RET_DIFFERENTIAL_STATE_DIMENSION_MISMATCH, "Incompatible differential state vector dimensions", VS_VISIBLE },
102 { RET_ALGEBRAIC_STATE_DIMENSION_MISMATCH, "Incompatible algebraic state vector dimensions", VS_VISIBLE },
103 { RET_CONTROL_DIMENSION_MISMATCH, "Incompatible control vector dimensions", VS_VISIBLE },
104 { RET_PARAMETER_DIMENSION_MISMATCH, "Incompatible parameter vector dimensions", VS_VISIBLE },
105 { RET_DISTURBANCE_DIMENSION_MISMATCH, "Incompatible disturbance vector dimensions", VS_VISIBLE },
106 { RET_OUTPUT_DIMENSION_MISMATCH, "Incompatible output vector dimensions", VS_VISIBLE },
107 { RET_MATRIX_NOT_SQUARE, "Operation requires square matrix", VS_VISIBLE },
108 
109 /* Sparse Solver */
110 { RET_LINEAR_SYSTEM_NUMERICALLY_SINGULAR, "Linear system could not be solved with required accuracy. Check whether the system is singular or ill-conditioned", VS_VISIBLE },
111 
112 /* Grid */
113 { RET_GRIDPOINT_SETUP_FAILED, "Failed to setup grid point", VS_VISIBLE },
114 { RET_GRIDPOINT_HAS_INVALID_TIME, "Unable to setup a grid point with this time", VS_VISIBLE },
115 { RET_CONFLICTING_GRIDS, "Conflicting grids detected", VS_VISIBLE },
116 { RET_TIME_INTERVAL_NOT_VALID, "The time interval is not valid / not in range", VS_VISIBLE },
117 { RET_INVALID_TIME_POINT, "A time point is not in its permissible range", VS_VISIBLE },
118 
119 /* Options */
120 { RET_OPTION_ALREADY_EXISTS, "An option with this name already exists", VS_VISIBLE },
121 { RET_OPTION_DOESNT_EXIST, "An option with this name does not exist", VS_VISIBLE },
122 { RET_OPTIONS_LIST_CORRUPTED, "Internal options list is corrupted", VS_VISIBLE },
123 { RET_INVALID_OPTION, "A user-defined option has an invalid value", VS_VISIBLE },
124 
125 /* Plotting */
126 { RET_PLOTTING_FAILED, "Unable to plot current window", VS_VISIBLE },
127 { RET_EMPTY_PLOT_DATA, "Unable to plot subplot as plot data is empty", VS_VISIBLE },
128 { RET_PLOT_WINDOW_CORRUPTED, "PlotWindow has corrupted list of subplots", VS_VISIBLE },
129 { RET_PLOT_COLLECTION_CORRUPTED, "PlotCollection has corrupted list of plot windows", VS_VISIBLE },
130 
131 /* Logging */
132 { RET_LOG_RECORD_CORRUPTED, "LogRecord has corrupted list of items", VS_VISIBLE },
133 { RET_LOG_ENTRY_DOESNT_EXIST, "An log entry with this name does not exist", VS_VISIBLE },
134 { RET_LOG_COLLECTION_CORRUPTED, "LogCollection has corrupted list of records", VS_VISIBLE },
135 
136 /* SimulationEnvironment */
137 { RET_BLOCK_DIMENSION_MISMATCH, "Blocks with incompatible dimensions", VS_VISIBLE },
138 { RET_NO_PROCESS_SPECIFIED, "No process has been specified", VS_VISIBLE },
139 { RET_NO_CONTROLLER_SPECIFIED, "No controller has been specified", VS_VISIBLE },
140 { RET_ENVIRONMENT_INIT_FAILED, "Unable to initialize simulation environment", VS_VISIBLE },
141 { RET_ENVIRONMENT_STEP_FAILED, "Unable to perform simulation environment step", VS_VISIBLE },
142 { RET_COMPUTATIONAL_DELAY_TOO_BIG, "Simulation stops as computational delay is too big", VS_VISIBLE },
143 { RET_COMPUTATIONAL_DELAY_NOT_SUPPORTED, "Simulation of computational delay is not yet supported", VS_VISIBLE },
144 
145 /* Block */
146 { RET_BLOCK_NOT_READY, "Block is not ready", VS_VISIBLE },
147 
148 /* Time */
149 { RET_NO_SYSTEM_TIME, "No system time available", VS_VISIBLE },
150 { RET_CLOCK_NOT_READY, "Unable to start the clock as it is not ready", VS_VISIBLE },
151 
152 /* Process */
153 { RET_PROCESS_INIT_FAILED, "Unable to initialize process", VS_VISIBLE },
154 { RET_PROCESS_STEP_FAILED, "Unable to perform process step", VS_VISIBLE },
155 { RET_PROCESS_STEP_FAILED_DISTURBANCE, "Unable to perform process step due to error in disturbance evaluation", VS_VISIBLE },
156 { RET_PROCESS_RUN_FAILED, "Unable to run process simulation", VS_VISIBLE },
157 { RET_NO_DYNAMICSYSTEM_SPECIFIED, "No dynamic system has been specified", VS_VISIBLE },
158 { RET_NO_INTEGRATIONALGORITHM_SPECIFIED, "No integration algorithm has been specified", VS_VISIBLE },
159 { RET_NO_DISCRETE_TIME_SYSTEMS_SUPPORTED, "Discrete-time systems are not yet supported", VS_VISIBLE },
160 { RET_WRONG_DISTURBANCE_HORIZON, "Process disturbance is defined over an incompatible time horizon", VS_VISIBLE },
161 
162 /* Actuator / Sensor */
163 { RET_ACTUATOR_INIT_FAILED, "Unable to initialize actuator", VS_VISIBLE },
164 { RET_ACTUATOR_STEP_FAILED, "Unable to perform actuator step", VS_VISIBLE },
165 { RET_SENSOR_INIT_FAILED, "Unable to initialize sensor", VS_VISIBLE },
166 { RET_SENSOR_STEP_FAILED, "Unable to perform sensor step", VS_VISIBLE },
167 { RET_GENERATING_NOISE_FAILED, "Unable to generate noise", VS_VISIBLE },
168 { RET_DELAYING_INPUTS_FAILED, "Unable to delay inputs", VS_VISIBLE },
169 { RET_DELAYING_OUTPUTS_FAILED, "Unable to delay outputs", VS_VISIBLE },
170 { RET_INCOMPATIBLE_ACTUATOR_SAMPLING_TIME, "Actuator sampling time has to be an integer multiple of dynamic system sample time", VS_VISIBLE },
171 { RET_INCOMPATIBLE_SENSOR_SAMPLING_TIME, "Sensor sampling time has to be an integer multiple of dynamic system sample time", VS_VISIBLE },
172 { RET_NO_DIFFERENT_NOISE_SAMPLING_FOR_DISCRETE, "When using discrete-time systems, noise has to be sampled equally for all components", VS_VISIBLE },
173 
174 /* Noise */
175 { RET_NO_NOISE_GENERATED, "No noise has been generated", VS_VISIBLE },
176 { RET_NO_NOISE_SETTINGS, "No noise settings has been defined", VS_VISIBLE },
177 { RET_INVALID_NOISE_SETTINGS, "Specified noise settings are invalid", VS_VISIBLE },
178 
179 /* Controller */
180 { RET_CONTROLLER_INIT_FAILED, "Unable to initialize controller", VS_VISIBLE },
181 { RET_CONTROLLER_STEP_FAILED, "Unable to perform controller step", VS_VISIBLE },
182 { RET_NO_ESTIMATOR_SPECIFIED, "No estimator has been specified", VS_VISIBLE },
183 { RET_NO_CONTROLLAW_SPECIFIED, "No control law has been specified", VS_VISIBLE },
184 { RET_NO_REALTIME_MODE_AVAILABLE, "Control law does not support real-time mode", VS_VISIBLE },
185 
186 /* DynamicControlUnit / Estimator / Optimizer */
187 { RET_DCU_INIT_FAILED, "Unable to initialize dynamic control unit", VS_VISIBLE },
188 { RET_DCU_STEP_FAILED, "Unable to perform step of dynamic control unit", VS_VISIBLE },
189 { RET_ESTIMATOR_INIT_FAILED, "Unable to initialize estimator", VS_VISIBLE },
190 { RET_ESTIMATOR_STEP_FAILED, "Unable to perform estimator step", VS_VISIBLE },
191 { RET_OPTIMIZER_INIT_FAILED, "Unable to initialize optimizer", VS_VISIBLE },
192 { RET_OPTIMIZER_STEP_FAILED, "Unable to perform optimizer step", VS_VISIBLE },
193 { RET_NO_OCP_SPECIFIED, "No optimal control problem has been specified", VS_VISIBLE },
194 { RET_NO_SOLUTIONALGORITHM_SPECIFIED, "No solution algorithm has been specified", VS_VISIBLE },
195 
196 /* ControlLaw */
197 { RET_CONTROLLAW_INIT_FAILED, "Unable to initialize feedback law", VS_VISIBLE },
198 { RET_CONTROLLAW_STEP_FAILED, "Unable to perform feedback law step", VS_VISIBLE },
199 { RET_NO_OPTIMIZER_SPECIFIED, "No optimizer has been specified", VS_VISIBLE },
200 { RET_INVALID_PID_OUTPUT_DIMENSION, "Invalid output dimension of PID controller, reset to 1", VS_VISIBLE },
201 
202 /* RealTimeAlgorithm */
203 { RET_IMMEDIATE_FEEDBACK_ONE_ITERATION, "Resetting maximum number of iterations to 1 as required for using immediate feedback", VS_VISIBLE },
204 
205 /* OutputTransformator */
206 { RET_OUTPUTTRANSFORMATOR_INIT_FAILED, "Unable to initialize output transformator", VS_VISIBLE },
207 { RET_OUTPUTTRANSFORMATOR_STEP_FAILED, "Unable to perform output transformator step", VS_VISIBLE },
208 
209 /* Function */
210 { RET_INVALID_USE_OF_FUNCTION, "Invalid use of the class function", VS_VISIBLE },
211 { RET_INFEASIBLE_CONSTRAINT, "Infeasible constraints detected", VS_VISIBLE },
212 { RET_ONLY_SUPPORTED_FOR_SYMBOLIC_FUNCTIONS, "This routine is for symbolic functions only", VS_VISIBLE },
213 { RET_INFEASIBLE_ALGEBRAIC_CONSTRAINT, "Infeasible algebraic constraints are not allowed and will be ignored", VS_VISIBLE },
214 { RET_ILLFORMED_ODE, "ODE needs to depend on all differential states", VS_VISIBLE },
215 
216 /* Expression */
217 { RET_PRECISION_OUT_OF_RANGE, "The requested precision is out of range", VS_VISIBLE },
218 { RET_ERROR_WHILE_PRINTING_A_FILE, "An error has occured while printing a file", VS_VISIBLE },
219 { RET_INDEX_OUT_OF_RANGE, "An index was not in the range", VS_VISIBLE },
220 { RET_INTERMEDIATE_STATE_HAS_NO_ARGUMENT, "The intermediate state has no argument", VS_VISIBLE },
221 { RET_DIMENSION_NOT_SPECIFIED, "The dimension of a array was not specified", VS_VISIBLE },
222 
223 /* Modeling Tools */
224 { RET_DDQ_DIMENSION_MISMATCH, "ddq argument must be of size 3x1", VS_VISIBLE },
225 { RET_CAN_ONLY_SOLVE_2ND_ORDER_KINVECS, "can only solve 2nd order KinVecs", VS_VISIBLE },
226 
227 
228 /* OBJECTIVE */
229 { RET_GAUSS_NEWTON_APPROXIMATION_NOT_SUPPORTED, "The objective does not support Gauss-Newton Hessian approximations", VS_VISIBLE },
230 { RET_REFERENCE_SHIFTING_WORKS_FOR_LSQ_TERMS_ONLY, "The reference shifting works only for LSQ objectives", VS_VISIBLE },
231 
232 /* Integrator */
233 { RET_TRIVIAL_RHS, "The dimension of the rhs is zero", VS_VISIBLE },
234 { RET_MISSING_INPUTS, "There are some inputs missing", VS_VISIBLE },
235 { RET_TO_SMALL_OR_NEGATIVE_TIME_INTERVAL, "The time interval was too small or negative", VS_VISIBLE },
236 { RET_FINAL_STEP_NOT_PERFORMED_YET, "The integration routine is not ready", VS_VISIBLE },
237 { RET_ALREADY_FROZEN, "The integrator is already freezing or frozen", VS_VISIBLE },
238 { RET_MAX_NUMBER_OF_STEPS_EXCEEDED, "The maximum number of steps has been exceeded", VS_VISIBLE },
239 { RET_WRONG_DEFINITION_OF_SEEDS, "The seeds are not set correctly", VS_VISIBLE },
240 { RET_NOT_FROZEN, "The mesh is not frozen and/or forward results not stored", VS_VISIBLE },
241 { RET_TO_MANY_DIFFERENTIAL_STATES, "There are to many differential states", VS_VISIBLE },
242 { RET_TO_MANY_DIFFERENTIAL_STATE_DERIVATIVES, "There are to many diff. state derivatives", VS_VISIBLE },
243 { RET_RK45_CAN_NOT_TREAT_DAE, "An explicit Runge-Kutta solver cannot treat DAEs", VS_VISIBLE },
244 { RET_CANNOT_TREAT_DAE, "The algorithm cannot treat DAEs.", VS_VISIBLE },
245 { RET_INPUT_HAS_WRONG_DIMENSION, "At least one of the inputs has a wrong dimension", VS_VISIBLE },
246 { RET_INPUT_OUT_OF_RANGE, "One of the inputs is out of range", VS_VISIBLE },
247 { RET_THE_DAE_INDEX_IS_TOO_LARGE, "The index of the DAE is larger than 1", VS_VISIBLE },
248 { RET_UNSUCCESSFUL_RETURN_FROM_INTEGRATOR_RK45, "The integration routine stopped as the required accuracy can not be obtained", VS_VISIBLE },
249 { RET_UNSUCCESSFUL_RETURN_FROM_INTEGRATOR_BDF, "The integration routine stopped as the required accuracy can not be obtained", VS_VISIBLE },
250 { RET_CANNOT_TREAT_DISCRETE_DE, "This integrator cannot treat discrete-time differential equations", VS_VISIBLE },
251 { RET_CANNOT_TREAT_CONTINUOUS_DE, "This integrator cannot treat time-continuous differential equations", VS_VISIBLE },
252 { RET_CANNOT_TREAT_IMPLICIT_DE, "This integrator cannot treat differential equations in implicit form", VS_VISIBLE },
253 { RET_CANNOT_TREAT_EXPLICIT_DE, "This integrator cannot treat differential equations in explicit form", VS_VISIBLE },
254 
255 /* DynamicDiscretization */
256 { RET_TO_MANY_DIFFERENTIAL_EQUATIONS, "The number of differential equations is too large", VS_VISIBLE },
257 { RET_BREAK_POINT_SETUP_FAILED, "The break point setup failed", VS_VISIBLE },
258 { RET_WRONG_DEFINITION_OF_STAGE_TRANSITIONS, "The definition of stage transitions is wrong", VS_VISIBLE },
259 { RET_TRANSITION_DEPENDS_ON_ALGEBRAIC_STATES, "A transition should never depend on algebraic states", VS_VISIBLE },
260 
261 /* OPTIMIZATION_ALGORITHM: */
262 { RET_NO_VALID_OBJECTIVE, "No valid objective found", VS_VISIBLE },
263 { RET_INCONSISTENT_BOUNDS, "The bounds are inconsistent", VS_VISIBLE },
264 { RET_INCOMPATIBLE_DIMENSIONS, "Incompatible dimensions detected", VS_VISIBLE },
265 { RET_GRID_SETUP_FAILED, "Discretization of the OCP failed", VS_VISIBLE },
266 { RET_OPTALG_INIT_FAILED, "Initialization of optimization algorithm failed", VS_VISIBLE },
267 { RET_OPTALG_STEP_FAILED, "Step of optimization algorithm failed", VS_VISIBLE },
268 { RET_OPTALG_FEEDBACK_FAILED, "Feedback step of optimization algorithm failed", VS_VISIBLE },
269 { RET_OPTALG_PREPARE_FAILED, "Preparation step of optimization algorithm failed", VS_VISIBLE },
270 { RET_OPTALG_SOLVE_FAILED, "Problem could not be solved with given optimization algorithm", VS_VISIBLE },
271 { RET_REALTIME_NO_INITIAL_VALUE, "No initial value has been specified", VS_VISIBLE },
272 
273 /* INTEGRATION_ALGORITHM: */
274 { RET_INTALG_INIT_FAILED, "Initialization of integration algorithm failed", VS_VISIBLE },
275 { RET_INTALG_INTEGRATION_FAILED, "Integration algorithm failed to integrate dynamic system", VS_VISIBLE },
276 { RET_INTALG_NOT_READY, "Integration algorithm has not been initialized", VS_VISIBLE },
277 
278 /* PLOT WINDOW */
279 { RET_PLOT_WINDOW_CAN_NOT_BE_OPEN, "ACADO was not able to open the plot window", VS_VISIBLE },
280 
281 /* NLP SOLVER */
282 { CONVERGENCE_ACHIEVED, "Convergence achieved", VS_VISIBLE },
283 { CONVERGENCE_NOT_YET_ACHIEVED, "Convergence not yet achieved", VS_VISIBLE },
284 { RET_NLP_INIT_FAILED, "Initialization of NLP solver failed", VS_VISIBLE },
285 { RET_NLP_STEP_FAILED, "Step of NLP solver failed", VS_VISIBLE },
286 { RET_NLP_SOLUTION_FAILED, "NLP solution failed", VS_VISIBLE },
287 { RET_INITIALIZE_FIRST, "Object needs to be initialized first", VS_VISIBLE },
288 { RET_SOLVER_NOT_SUTIABLE_FOR_REAL_TIME_MODE, "The specified NLP solver is not designed for a real-time mode", VS_VISIBLE },
289 { RET_ILLFORMED_HESSIAN_MATRIX, "Hessian matrix is too ill-conditioned to continue", VS_VISIBLE },
290 { RET_NONSYMMETRIC_HESSIAN_MATRIX, "Hessian matrix is not symmetric, proceeding with symmetrized Hessian", VS_VISIBLE },
291 { RET_UNABLE_TO_EVALUATE_OBJECTIVE, "Evaluation of objective function failed", VS_VISIBLE },
292 { RET_UNABLE_TO_EVALUATE_CONSTRAINTS, "Evaluation of constraints failed", VS_VISIBLE },
293 { 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> )", VS_VISIBLE },
294 { RET_NEED_TO_ACTIVATE_RTI, "Feedback step requires real-time iterations to be activated. Use set( USE_REALTIME_ITERATIONS,YES ) to do so", VS_VISIBLE },
295 
296 /* CONIC SOLVER */
297 { RET_CONIC_PROGRAM_INFEASIBLE, "The optimization problem is infeasible", VS_VISIBLE },
298 { RET_CONIC_PROGRAM_SOLUTION_FAILED, "Conic Program solution failed. The optimization problem might be infeasible", VS_VISIBLE },
299 { RET_CONIC_PROGRAM_NOT_SOLVED, "The Conic Program has not been solved successfully", VS_VISIBLE },
300 
301 /* CP SOLVER */
302 { RET_UNABLE_TO_CONDENSE, "Unable to condense banded CP", VS_VISIBLE },
303 { RET_UNABLE_TO_EXPAND, "Unable to expand condensed CP", VS_VISIBLE },
304 { RET_NEED_TO_CONDENSE_FIRST, "Condensing cannot be frozen as banded CP needs to be condensed first", VS_VISIBLE },
305 { RET_BANDED_CP_INIT_FAILED, "Initialization of banded CP solver failed", VS_VISIBLE },
306 { RET_BANDED_CP_SOLUTION_FAILED, "Solution of banded CP failed", VS_VISIBLE },
307 
308 /* OCP */
309 { RET_TRANSITION_NOT_DEFINED, "No transition function found", VS_VISIBLE },
310 
311 /* QP SOLVER */
312 { RET_QP_INIT_FAILED, "QP initialization failed", VS_VISIBLE },
313 { RET_QP_SOLUTION_FAILED, "QP solution failed", VS_VISIBLE },
314 { RET_QP_SOLUTION_REACHED_LIMIT, "QP solution stopped as iteration limit is reached", VS_VISIBLE },
315 { RET_QP_INFEASIBLE, "QP solution failed due to infeasibility", VS_VISIBLE },
316 { RET_QP_UNBOUNDED, "QP solution failed due to unboundedness", VS_VISIBLE },
317 { RET_QP_NOT_SOLVED, "QP has not been solved", VS_VISIBLE },
318 { RET_RELAXING_QP, "QP needs to be relaxed due to infeasibility", VS_VISIBLE },
319 { RET_COULD_NOT_RELAX_QP, "QP could not be relaxed", VS_VISIBLE },
320 { RET_QP_SOLVER_CAN_ONLY_SOLVE_QP, "The QP solver can not deal with general conic problems.", VS_VISIBLE },
321 { RET_QP_HAS_INCONSISTENT_BOUNDS, "QP cannot be solved due to inconsistent bounds", VS_VISIBLE },
322 { RET_UNABLE_TO_HOTSTART_QP, "Unable to hotstart QP with given solver", VS_VISIBLE },
323 
324 /* MPC SOLVER */
325 { RET_NONPOSITIVE_WEIGHT, "Weighting matrices must be positive definite", VS_VISIBLE },
326 { RET_INITIAL_CHOLESKY_FAILED, "Setting up initial Cholesky decompostion failed", VS_VISIBLE },
327 { RET_HOMOTOPY_STEP_FAILED, "Unable to perform homotopy step", VS_VISIBLE },
328 { RET_STEPDIRECTION_DETERMINATION_FAILED, "Determination of step direction failed", VS_VISIBLE },
329 { RET_STEPDIRECTION_FAILED_CHOLESKY, "Abnormal termination due to Cholesky factorisation", VS_VISIBLE },
330 { RET_STEPLENGTH_DETERMINATION_FAILED, "Determination of step direction failed", VS_VISIBLE },
331 { RET_OPTIMAL_SOLUTION_FOUND, "Optimal solution of neighbouring QP found", VS_VISIBLE },
332 { RET_MAX_NWSR_REACHED, "Maximum number of working set recalculations performed", VS_VISIBLE },
333 { RET_MATRIX_NOT_SPD, "DMatrix not positive definite", VS_VISIBLE },
334 
335 /* CODE EXPORT */
336 { RET_CODE_EXPORT_SUCCESSFUL, "Code generation successful", VS_VISIBLE },
337 { RET_UNABLE_TO_EXPORT_CODE, "Unable to generate code", VS_VISIBLE },
338 { RET_INVALID_OBJECTIVE_FOR_CODE_EXPORT, "Only standard LSQ objective supported for code generation", VS_VISIBLE },
339 { RET_NO_DISCRETE_ODE_FOR_CODE_EXPORT, "No discrete-time ODEs supported for code generation", VS_VISIBLE },
340 { RET_ONLY_ODE_FOR_CODE_EXPORT, "Only ODEs supported for code generation", VS_VISIBLE },
341 { RET_ONLY_STATES_AND_CONTROLS_FOR_CODE_EXPORT, "No parameters, disturbances or algebraic states supported for code generation", VS_VISIBLE },
342 { RET_ONLY_EQUIDISTANT_GRID_FOR_CODE_EXPORT, "Only equidistant evaluation grids supported for code generation", VS_VISIBLE },
343 { RET_ONLY_BOUNDS_FOR_CODE_EXPORT, "Only state and control bounds supported for code generation", VS_VISIBLE },
344 { RET_QPOASES_EMBEDDED_NOT_FOUND, "Embedded qpOASES code not found", VS_VISIBLE },
345 { RET_UNABLE_TO_EXPORT_STATEMENT, "Unable to export statement due to incomplete definition", VS_VISIBLE },
346 { RET_INVALID_CALL_TO_EXPORTED_FUNCTION, "Invalid call to export functions (check number of calling arguments)", VS_VISIBLE },
347 
348 /* IMPORTANT: Terminal list element! */
349 { TERMINAL_LIST_ELEMENT, " ", VS_HIDDEN }
350 };
351 
352 
353 //
354 // HELPER FUNCTIONS:
355 //
356 
357 
358 // Converts returnValueLevel enum type to a const char*
360 {
361  switch ( level )
362  {
363  case LVL_DEBUG:
364  return COL_DEBUG"Debug";
365 
366  case LVL_FATAL:
367  return COL_FATAL"Fatal error";
368 
369  case LVL_ERROR:
370  return COL_ERROR"Error";
371 
372  case LVL_WARNING:
373  return COL_WARNING"Warning";
374 
375  case LVL_INFO:
376  return COL_INFO"Information";
377  }
378 
379  return 0;
380 }
381 
382 // Converts returnValueType enum type to a const char*
385  while( (p->key != type) && (p->key != TERMINAL_LIST_ELEMENT) ) p++;
386  return p->data;
387 }
388 
393 {
394 public:
396  std::vector<const char*> messages;
397 };
398 
399 //
400 // PUBLIC MEMBER FUNCTIONS:
401 //
402 
403 
404 /* Constructor used by the ACADOERROR and similar macros.
405  *
406  */
408  data = new returnValueData();
409  data->owner = this;
410  data->messages.push_back(msg);
411  status = STATUS_UNHANDLED;
412  type = _type;
413  level = _level;
414 }
415 
416 /* Construct default returnValue.
417  *
418  */
420 
421 /* Construct returnValue only from typedef.
422  *
423  */
425 
426 /* Construct returnValue from int, for compatibility
427  *
428  */
430  type = returnValueType(_type);
431 }
432 
433 /* Copy constructor with minimum performance cost.
434  * Newly constructed instance takes ownership of data.
435  */
437  // Copy data
438  if (old.data) {
439  data = old.data;
440  data->owner = this;
441  } else {
442  data = 0;
443  }
444  // Copy details
445  type = old.type;
446  level = old.level;
447  status = old.status;
448 }
449 
451  return level;
452 }
453 
454 /* Compares the returnValue type to its enum
455  *
456  */
458  return type != cmp_type;
459 }
460 
461 /* Compares the returnValue type to its enum
462  *
463  */
465  return type == cmp_type;
466 }
467 
468 /* Returns true if return value type is not SUCCESSFUL_RETURN
469  *
470  */
472  return type != SUCCESSFUL_RETURN;
473 }
474 
475 /* Assignment operator.
476  * Left hand side instance takes ownership of data.
477  */
479  // Clean up data if already existing
480  if (data && (data->owner == this)) delete data;
481 
482  // Copy data
483  if (old.data) {
484  data = old.data;
485  data->owner = this;
486  } else {
487  data = 0;
488  }
489  // Copy details
490  type = old.type;
491  level = old.level;
492  status = old.status;
493 
494  return *this;
495 }
496 
497 /* Compatibility function, allows returnValue to be used as a number, similar to a enum.
498  *
499  */
500 returnValue::operator int() {
501  return type;
502 }
503 
504 /* Destroys data instance only if it owns it
505  *
506  */
508  if ( data )
509  {
510  if (data->owner == this)
511  {
512  // If is not succesful and was not handled yet, by default print message to standard output
513  if (status != STATUS_HANDLED)
514  {
515  print();
516  }
517 
518  if ( data )
519  {
520  delete data;
521  }
522 
523 #ifdef ACADO_WITH_TESTING
524  if (level == LVL_FATAL || level == LVL_ERROR || level == LVL_WARNING)
525 #else
526  if (level == LVL_FATAL)
527 #endif
528  {
529  abort();
530  }
531  }
532  }
533 }
534 
535 /* Constructor used by the ACADOERROR and similar macros. Special case.
536  * Constructs returnValue from old one, changing level and adding message
537  */
538 returnValue::returnValue(const char* msg, returnValueLevel _level, const returnValue& old) {
539  if (old.data) {
540  data = old.data;
541  data->owner = this;
542  data->messages.push_back(msg);
543  }
545  level = _level;
546  type = old.type;
547 }
548 
549 /* Adds another message to the end of messages list.
550  *
551  */
553  if (!data) {
554  data = new returnValueData();
555  data->owner = this;
556  }
557  data->messages.push_back(msg);
558  return *this;
559 }
560 
561 /* Change the importance level of the returned value
562  *
563  */
565  level = _level;
566  return *this;
567 }
568 
569 /* Change the type of the returned message
570  *
571  */
573 
574  type = _type;
575  return *this;
576 }
577 
578 /* Prints all messages to the standard output.
579  *
580  */
582 
583  cout << COL_INFO"[ACADO] " << returnValueLevelToString( level )
584  << ": " << returnValueTypeToString( type ) << COL_INFO << endl;
585 
586  if ( data )
587  for (vector<const char*>::iterator it = data->messages.begin(); it != data->messages.end(); it++)
588  cout << " " << (*it) << endl;
589  cout << endl;
590 
592 }
593 
594 /* Prints only the most basic information, no messages, to the standard output.
595  *
596  */
598 
599  std::cout << returnValueLevelToString(level) << ": " << returnValueTypeToString(type) << std::endl;
601 }
602 
603 // Logging class
604 
606 {
607  cout << COL_INFO"[ACADO] " << returnValueLevelToString( level ) << ": " << COL_INFO;
608 
609  return cout;
610 }
611 
613 
614 
615 /*
616  * end of file
617  */
returnValue was not yet handled by user
Returned value is a information.
Lowest level, the debug level.
const char * returnValueTypeToString(returnValueType type)
bool operator!() const
returnValue & addMessage(const char *msg)
returnValueLevel getLevel() const
returnValue & changeLevel(returnValueLevel level)
#define COL_DEBUG
Allows to pass back messages to the calling function.
#define COL_INFO
std::vector< const char * > messages
Returned value is a error.
#define COL_ERROR
#define CLOSE_NAMESPACE_ACADO
returnValueType
Defines all symbols for global return values.
Returned value is a warning.
bool operator==(returnValueType cmp_type) const
#define COL_WARNING
returnValueLevel
ReturnValueList returnValueList[]
Defines all pairs of global return values and messages within the ACADO Toolkit.
Data structure for entries in returnValueList.
VisibilityStatus globalVisibilityStatus
Returned value is a fatal error, assert like use, aborts execution is unhandled.
returnValue & operator=(const returnValue &old)
std::ostream & get(returnValueLevel level)
bool operator!=(returnValueType cmp_type) const
returnValueLevel level
const char * returnValueLevelToString(returnValueLevel level)
returnValue & changeType(returnValueType type)
#define BEGIN_NAMESPACE_ACADO
returnValue was handled by user
returnValueData * data
returnValueType type
#define COL_FATAL


acado
Author(s): Milan Vukov, Rien Quirynen
autogenerated on Mon Jun 10 2019 12:34:27