acado_message_handling.cpp
Go to the documentation of this file.
00001 /*
00002  *    This file is part of ACADO Toolkit.
00003  *
00004  *    ACADO Toolkit -- A Toolkit for Automatic Control and Dynamic Optimization.
00005  *    Copyright (C) 2008-2014 by Boris Houska, Hans Joachim Ferreau,
00006  *    Milan Vukov, Rien Quirynen, KU Leuven.
00007  *    Developed within the Optimization in Engineering Center (OPTEC)
00008  *    under supervision of Moritz Diehl. All rights reserved.
00009  *
00010  *    ACADO Toolkit is free software; you can redistribute it and/or
00011  *    modify it under the terms of the GNU Lesser General Public
00012  *    License as published by the Free Software Foundation; either
00013  *    version 3 of the License, or (at your option) any later version.
00014  *
00015  *    ACADO Toolkit is distributed in the hope that it will be useful,
00016  *    but WITHOUT ANY WARRANTY; without even the implied warranty of
00017  *    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
00018  *    Lesser General Public License for more details.
00019  *
00020  *    You should have received a copy of the GNU Lesser General Public
00021  *    License along with ACADO Toolkit; if not, write to the Free Software
00022  *    Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA
00023  *
00024  */
00025 
00026 
00033 #include <string.h>
00034 
00035 #ifdef __MATLAB__
00036  #include"mex.h"
00037 #endif
00038 
00039 #include <acado/utils/acado_message_handling.hpp>
00040 #include <acado/utils/acado_utils.hpp>
00041 
00042 using namespace std;
00043 
00044 BEGIN_NAMESPACE_ACADO
00045 
00055 typedef struct {
00056         returnValueType key;                                            
00057         const char* data;                                                       
00058         VisibilityStatus globalVisibilityStatus;        
00060 } ReturnValueList;
00061 
00070 ReturnValueList returnValueList[] =
00071 {
00072 /* miscellaneous */
00073 { SUCCESSFUL_RETURN,                                                    "Successful return", VS_VISIBLE },
00074 { RET_DIV_BY_ZERO,                                                              "Division by zero", VS_VISIBLE },
00075 { RET_INDEX_OUT_OF_BOUNDS,                                              "Index out of bounds", VS_VISIBLE },
00076 { RET_INVALID_ARGUMENTS,                                                "At least one of the arguments is invalid", VS_VISIBLE },
00077 { RET_ERROR_UNDEFINED,                                                  "Error number undefined", VS_VISIBLE },
00078 { RET_WARNING_UNDEFINED,                                                "Warning number undefined", VS_VISIBLE },
00079 { RET_INFO_UNDEFINED,                                                   "Info number undefined", VS_VISIBLE },
00080 { RET_EWI_UNDEFINED,                                                    "Error/warning/info number undefined", VS_VISIBLE },
00081 { RET_AVAILABLE_WITH_LINUX_ONLY,                                "This function is available under Linux only", VS_HIDDEN },
00082 { RET_UNKNOWN_BUG,                                                              "The error occured is not yet known", VS_VISIBLE },
00083 { RET_PRINTLEVEL_CHANGED,                                               "Print level changed", VS_VISIBLE },
00084 { RET_NOT_YET_IMPLEMENTED,                                              "Requested function is not yet implemented", VS_VISIBLE },
00085 { RET_NOT_IMPLEMENTED_YET,                                              "Requested function is not yet implemented", VS_VISIBLE },
00086 { RET_NOT_IMPLEMENTED_IN_BASE_CLASS,                    "Requested function is not implemented within this class", VS_VISIBLE },
00087 { RET_ASSERTION,                                                                "An assertion has been violated", VS_VISIBLE },
00088 { RET_MEMBER_NOT_INITIALISED,                                   "Requested member has not been initialised", VS_VISIBLE },
00089 { RET_ABSTRACT_BASE_CLASS,                                              "Invalid call to member function of abstract base class", VS_VISIBLE },
00090 { RET_NO_DATA_FOUND,                                                    "There has no data been found", VS_VISIBLE },
00091 { RET_INPUT_DIMENSION_MISMATCH,                                 "The dimensions of the input are wrong", VS_VISIBLE },
00092 { RET_STRING_EXCEEDS_LENGTH,                                    "String exceeds maximum length", VS_VISIBLE },
00093 
00094 /* IO utils: */
00095 { RET_FILE_NOT_FOUND,                                                   "The file has not been found", VS_VISIBLE },
00096 { RET_FILE_CAN_NOT_BE_OPENED,                                   "The file can not be opened", VS_VISIBLE },
00097 { RET_CAN_NOT_WRITE_INTO_FILE,                                  "The routine has no write access or writing into the file failed", VS_VISIBLE },
00098 { RET_FILE_CAN_NOT_BE_CLOSED,                                   "The file could not be closed", VS_VISIBLE },
00099 { RET_FILE_HAS_NO_VALID_ENTRIES,                                "The file has no valid entries", VS_VISIBLE },
00100 { RET_DOES_DIRECTORY_EXISTS,                                    "Could not open file, check if given directory exists", VS_VISIBLE },
00101 
00102 /* DMatrix/DVector */
00103 { RET_VECTOR_DIMENSION_MISMATCH,                                "Incompatible vector dimensions", VS_VISIBLE },
00104 { RET_DIFFERENTIAL_STATE_DIMENSION_MISMATCH,    "Incompatible differential state vector dimensions", VS_VISIBLE },
00105 { RET_ALGEBRAIC_STATE_DIMENSION_MISMATCH,               "Incompatible algebraic state vector dimensions", VS_VISIBLE },
00106 { RET_CONTROL_DIMENSION_MISMATCH,                               "Incompatible control vector dimensions", VS_VISIBLE },
00107 { RET_PARAMETER_DIMENSION_MISMATCH,                             "Incompatible parameter vector dimensions", VS_VISIBLE },
00108 { RET_DISTURBANCE_DIMENSION_MISMATCH,                   "Incompatible disturbance vector dimensions", VS_VISIBLE },
00109 { RET_OUTPUT_DIMENSION_MISMATCH,                                "Incompatible output vector dimensions", VS_VISIBLE },
00110 { RET_MATRIX_NOT_SQUARE,                                                "Operation requires square matrix", VS_VISIBLE },
00111 
00112 /* Sparse Solver */
00113 { 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 },
00114 
00115 /* Grid */
00116 { RET_GRIDPOINT_SETUP_FAILED,                                   "Failed to setup grid point", VS_VISIBLE },
00117 { RET_GRIDPOINT_HAS_INVALID_TIME,                               "Unable to setup a grid point with this time", VS_VISIBLE },
00118 { RET_CONFLICTING_GRIDS,                                                "Conflicting grids detected", VS_VISIBLE },
00119 { RET_TIME_INTERVAL_NOT_VALID,                                  "The time interval is not valid / not in range", VS_VISIBLE },
00120 { RET_INVALID_TIME_POINT,                                               "A time point is not in its permissible range", VS_VISIBLE },
00121 
00122 /* Options */
00123 { RET_OPTION_ALREADY_EXISTS,                                    "An option with this name already exists", VS_VISIBLE },
00124 { RET_OPTION_DOESNT_EXIST,                                              "An option with this name does not exist", VS_VISIBLE },
00125 { RET_OPTIONS_LIST_CORRUPTED,                                   "Internal options list is corrupted", VS_VISIBLE },
00126 { RET_INVALID_OPTION,                                                   "A user-defined option has an invalid value", VS_VISIBLE },
00127 
00128 /* Plotting */
00129 { RET_PLOTTING_FAILED,                                                  "Unable to plot current window", VS_VISIBLE },
00130 { RET_EMPTY_PLOT_DATA,                                                  "Unable to plot subplot as plot data is empty", VS_VISIBLE },
00131 { RET_PLOT_WINDOW_CORRUPTED,                                    "PlotWindow has corrupted list of subplots", VS_VISIBLE },
00132 { RET_PLOT_COLLECTION_CORRUPTED,                                "PlotCollection has corrupted list of plot windows", VS_VISIBLE },
00133 
00134 /* Logging */
00135 { RET_LOG_RECORD_CORRUPTED,                                             "LogRecord has corrupted list of items", VS_VISIBLE },
00136 { RET_LOG_ENTRY_DOESNT_EXIST,                                   "An log entry with this name does not exist", VS_VISIBLE },
00137 { RET_LOG_COLLECTION_CORRUPTED,                                 "LogCollection has corrupted list of records", VS_VISIBLE },
00138 
00139 /* SimulationEnvironment */
00140 { RET_BLOCK_DIMENSION_MISMATCH,                                 "Blocks with incompatible dimensions", VS_VISIBLE },
00141 { RET_NO_PROCESS_SPECIFIED,                                             "No process has been specified", VS_VISIBLE },
00142 { RET_NO_CONTROLLER_SPECIFIED,                                  "No controller has been specified", VS_VISIBLE },
00143 { RET_ENVIRONMENT_INIT_FAILED,                                  "Unable to initialize simulation environment", VS_VISIBLE },
00144 { RET_ENVIRONMENT_STEP_FAILED,                                  "Unable to perform simulation environment step", VS_VISIBLE },
00145 { RET_COMPUTATIONAL_DELAY_TOO_BIG,                              "Simulation stops as computational delay is too big", VS_VISIBLE },
00146 { RET_COMPUTATIONAL_DELAY_NOT_SUPPORTED,                "Simulation of computational delay is not yet supported", VS_VISIBLE },
00147 
00148 /* Block */
00149 { RET_BLOCK_NOT_READY,                                                  "Block is not ready", VS_VISIBLE },
00150 
00151 /* Time */
00152 { RET_NO_SYSTEM_TIME,                                                   "No system time available", VS_VISIBLE },
00153 { RET_CLOCK_NOT_READY,                                                  "Unable to start the clock as it is not ready", VS_VISIBLE },
00154 
00155 /* Process */
00156 { RET_PROCESS_INIT_FAILED,                                              "Unable to initialize process", VS_VISIBLE },
00157 { RET_PROCESS_STEP_FAILED,                                              "Unable to perform process step", VS_VISIBLE },
00158 { RET_PROCESS_STEP_FAILED_DISTURBANCE,                  "Unable to perform process step due to error in disturbance evaluation", VS_VISIBLE },
00159 { RET_PROCESS_RUN_FAILED,                                               "Unable to run process simulation", VS_VISIBLE },
00160 { RET_NO_DYNAMICSYSTEM_SPECIFIED,                               "No dynamic system has been specified", VS_VISIBLE },
00161 { RET_NO_INTEGRATIONALGORITHM_SPECIFIED,                "No integration algorithm has been specified", VS_VISIBLE },
00162 { RET_NO_DISCRETE_TIME_SYSTEMS_SUPPORTED,               "Discrete-time systems are not yet supported", VS_VISIBLE },
00163 { RET_WRONG_DISTURBANCE_HORIZON,                                "Process disturbance is defined over an incompatible time horizon", VS_VISIBLE },
00164 
00165 /* Actuator / Sensor */
00166 { RET_ACTUATOR_INIT_FAILED,                                             "Unable to initialize actuator", VS_VISIBLE },
00167 { RET_ACTUATOR_STEP_FAILED,                                             "Unable to perform actuator step", VS_VISIBLE },
00168 { RET_SENSOR_INIT_FAILED,                                               "Unable to initialize sensor", VS_VISIBLE },
00169 { RET_SENSOR_STEP_FAILED,                                               "Unable to perform sensor step", VS_VISIBLE },
00170 { RET_GENERATING_NOISE_FAILED,                                  "Unable to generate noise", VS_VISIBLE },
00171 { RET_DELAYING_INPUTS_FAILED,                                   "Unable to delay inputs", VS_VISIBLE },
00172 { RET_DELAYING_OUTPUTS_FAILED,                                  "Unable to delay outputs", VS_VISIBLE },
00173 { RET_INCOMPATIBLE_ACTUATOR_SAMPLING_TIME,              "Actuator sampling time has to be an integer multiple of dynamic system sample time", VS_VISIBLE },
00174 { RET_INCOMPATIBLE_SENSOR_SAMPLING_TIME,                "Sensor sampling time has to be an integer multiple of dynamic system sample time", VS_VISIBLE },
00175 { RET_NO_DIFFERENT_NOISE_SAMPLING_FOR_DISCRETE, "When using discrete-time systems, noise has to be sampled equally for all components", VS_VISIBLE },
00176 
00177 /* Noise */
00178 { RET_NO_NOISE_GENERATED,                                               "No noise has been generated", VS_VISIBLE },
00179 { RET_NO_NOISE_SETTINGS,                                                "No noise settings has been defined", VS_VISIBLE },
00180 { RET_INVALID_NOISE_SETTINGS,                                   "Specified noise settings are invalid", VS_VISIBLE },
00181 
00182 /* Controller */
00183 { RET_CONTROLLER_INIT_FAILED,                                   "Unable to initialize controller", VS_VISIBLE },
00184 { RET_CONTROLLER_STEP_FAILED,                                   "Unable to perform controller step", VS_VISIBLE },
00185 { RET_NO_ESTIMATOR_SPECIFIED,                                   "No estimator has been specified", VS_VISIBLE },
00186 { RET_NO_CONTROLLAW_SPECIFIED,                                  "No control law has been specified", VS_VISIBLE },
00187 { RET_NO_REALTIME_MODE_AVAILABLE,                               "Control law does not support real-time mode", VS_VISIBLE },
00188 
00189 /* DynamicControlUnit / Estimator / Optimizer */
00190 { RET_DCU_INIT_FAILED,                                                  "Unable to initialize dynamic control unit", VS_VISIBLE },
00191 { RET_DCU_STEP_FAILED,                                                  "Unable to perform step of dynamic control unit", VS_VISIBLE },
00192 { RET_ESTIMATOR_INIT_FAILED,                                    "Unable to initialize estimator", VS_VISIBLE },
00193 { RET_ESTIMATOR_STEP_FAILED,                                    "Unable to perform estimator step", VS_VISIBLE },
00194 { RET_OPTIMIZER_INIT_FAILED,                                    "Unable to initialize optimizer", VS_VISIBLE },
00195 { RET_OPTIMIZER_STEP_FAILED,                                    "Unable to perform optimizer step", VS_VISIBLE },
00196 { RET_NO_OCP_SPECIFIED,                                                 "No optimal control problem has been specified", VS_VISIBLE },
00197 { RET_NO_SOLUTIONALGORITHM_SPECIFIED,                   "No solution algorithm has been specified", VS_VISIBLE },
00198 
00199 /* ControlLaw */
00200 { RET_CONTROLLAW_INIT_FAILED,                                   "Unable to initialize feedback law", VS_VISIBLE },
00201 { RET_CONTROLLAW_STEP_FAILED,                                   "Unable to perform feedback law step", VS_VISIBLE },
00202 { RET_NO_OPTIMIZER_SPECIFIED,                                   "No optimizer has been specified", VS_VISIBLE },
00203 { RET_INVALID_PID_OUTPUT_DIMENSION,                             "Invalid output dimension of PID controller, reset to 1", VS_VISIBLE },
00204 
00205 /* RealTimeAlgorithm */
00206 { RET_IMMEDIATE_FEEDBACK_ONE_ITERATION,                 "Resetting maximum number of iterations to 1 as required for using immediate feedback", VS_VISIBLE },
00207 
00208 /* OutputTransformator */
00209 { RET_OUTPUTTRANSFORMATOR_INIT_FAILED,                  "Unable to initialize output transformator", VS_VISIBLE },
00210 { RET_OUTPUTTRANSFORMATOR_STEP_FAILED,                  "Unable to perform output transformator step", VS_VISIBLE },
00211 
00212 /* Function */
00213 { RET_INVALID_USE_OF_FUNCTION,                                  "Invalid use of the class function", VS_VISIBLE },
00214 { RET_INFEASIBLE_CONSTRAINT,                                    "Infeasible constraints detected", VS_VISIBLE },
00215 { RET_ONLY_SUPPORTED_FOR_SYMBOLIC_FUNCTIONS,    "This routine is for symbolic functions only", VS_VISIBLE },
00216 { RET_INFEASIBLE_ALGEBRAIC_CONSTRAINT,                  "Infeasible algebraic constraints are not allowed and will be ignored", VS_VISIBLE },
00217 { RET_ILLFORMED_ODE,                                                    "ODE needs to depend on all differential states", VS_VISIBLE },
00218 
00219 /* Expression */
00220 { RET_PRECISION_OUT_OF_RANGE,                                   "The requested precision is out of range", VS_VISIBLE },
00221 { RET_ERROR_WHILE_PRINTING_A_FILE,                              "An error has occured while printing a file", VS_VISIBLE },
00222 { RET_INDEX_OUT_OF_RANGE,                                               "An index was not in the range", VS_VISIBLE },
00223 { RET_INTERMEDIATE_STATE_HAS_NO_ARGUMENT,               "The intermediate state has no argument", VS_VISIBLE },
00224 { RET_DIMENSION_NOT_SPECIFIED,                                  "The dimension of a array was not specified", VS_VISIBLE },
00225 
00226 /* Modeling Tools */
00227 { RET_DDQ_DIMENSION_MISMATCH,                                   "ddq argument must be of size 3x1", VS_VISIBLE },
00228 { RET_CAN_ONLY_SOLVE_2ND_ORDER_KINVECS,                 "can only solve 2nd order KinVecs", VS_VISIBLE },
00229 
00230 
00231 /* OBJECTIVE */
00232 { RET_GAUSS_NEWTON_APPROXIMATION_NOT_SUPPORTED, "The objective does not support Gauss-Newton Hessian approximations", VS_VISIBLE },
00233 { RET_REFERENCE_SHIFTING_WORKS_FOR_LSQ_TERMS_ONLY,      "The reference shifting works only for LSQ objectives", VS_VISIBLE },
00234 
00235 /* Integrator */
00236 { RET_TRIVIAL_RHS,                                                              "The dimension of the rhs is zero", VS_VISIBLE },
00237 { RET_MISSING_INPUTS,                                                   "There are some inputs missing", VS_VISIBLE },
00238 { RET_TO_SMALL_OR_NEGATIVE_TIME_INTERVAL,               "The time interval was too small or negative", VS_VISIBLE },
00239 { RET_FINAL_STEP_NOT_PERFORMED_YET,                             "The integration routine is not ready", VS_VISIBLE },
00240 { RET_ALREADY_FROZEN,                                                   "The integrator is already freezing or frozen", VS_VISIBLE },
00241 { RET_MAX_NUMBER_OF_STEPS_EXCEEDED,                             "The maximum number of steps has been exceeded", VS_VISIBLE },
00242 { RET_WRONG_DEFINITION_OF_SEEDS,                                "The seeds are not set correctly", VS_VISIBLE },
00243 { RET_NOT_FROZEN,                                                               "The mesh is not frozen and/or forward results not stored", VS_VISIBLE },
00244 { RET_TO_MANY_DIFFERENTIAL_STATES,                              "There are to many differential states", VS_VISIBLE },
00245 { RET_TO_MANY_DIFFERENTIAL_STATE_DERIVATIVES,   "There are to many diff. state derivatives", VS_VISIBLE },
00246 { RET_RK45_CAN_NOT_TREAT_DAE,                                   "An explicit Runge-Kutta solver cannot treat DAEs", VS_VISIBLE },
00247 { RET_CANNOT_TREAT_DAE,                                                 "The algorithm cannot treat DAEs.", VS_VISIBLE },
00248 { RET_INPUT_HAS_WRONG_DIMENSION,                                "At least one of the inputs has a wrong dimension", VS_VISIBLE },
00249 { RET_INPUT_OUT_OF_RANGE,                                               "One of the inputs is out of range", VS_VISIBLE },
00250 { RET_THE_DAE_INDEX_IS_TOO_LARGE,                               "The index of the DAE is larger than 1", VS_VISIBLE },
00251 { RET_UNSUCCESSFUL_RETURN_FROM_INTEGRATOR_RK45, "The integration routine stopped as the required accuracy can not be obtained", VS_VISIBLE },
00252 { RET_UNSUCCESSFUL_RETURN_FROM_INTEGRATOR_BDF,  "The integration routine stopped as the required accuracy can not be obtained", VS_VISIBLE },
00253 { RET_CANNOT_TREAT_DISCRETE_DE,                                 "This integrator cannot treat discrete-time differential equations", VS_VISIBLE },
00254 { RET_CANNOT_TREAT_CONTINUOUS_DE,                               "This integrator cannot treat time-continuous differential equations", VS_VISIBLE },
00255 { RET_CANNOT_TREAT_IMPLICIT_DE,                                 "This integrator cannot treat differential equations in implicit form", VS_VISIBLE },
00256 { RET_CANNOT_TREAT_EXPLICIT_DE,                                 "This integrator cannot treat differential equations in explicit form", VS_VISIBLE },
00257 
00258 /* DynamicDiscretization */
00259 { RET_TO_MANY_DIFFERENTIAL_EQUATIONS,                   "The number of differential equations is too large", VS_VISIBLE },
00260 { RET_BREAK_POINT_SETUP_FAILED,                                 "The break point setup failed", VS_VISIBLE },
00261 { RET_WRONG_DEFINITION_OF_STAGE_TRANSITIONS,    "The definition of stage transitions is wrong", VS_VISIBLE },
00262 { RET_TRANSITION_DEPENDS_ON_ALGEBRAIC_STATES,   "A transition should never depend on algebraic states", VS_VISIBLE },
00263 
00264 /* OPTIMIZATION_ALGORITHM: */
00265 { RET_NO_VALID_OBJECTIVE,                                               "No valid objective found", VS_VISIBLE },
00266 { RET_INCONSISTENT_BOUNDS,                                              "The bounds are inconsistent", VS_VISIBLE },
00267 { RET_INCOMPATIBLE_DIMENSIONS,                                  "Incompatible dimensions detected", VS_VISIBLE },
00268 { RET_GRID_SETUP_FAILED,                                                "Discretization of the OCP failed", VS_VISIBLE },
00269 { RET_OPTALG_INIT_FAILED,                                               "Initialization of optimization algorithm failed", VS_VISIBLE },
00270 { RET_OPTALG_STEP_FAILED,                                               "Step of optimization algorithm failed", VS_VISIBLE },
00271 { RET_OPTALG_FEEDBACK_FAILED,                                   "Feedback step of optimization algorithm failed", VS_VISIBLE },
00272 { RET_OPTALG_PREPARE_FAILED,                                    "Preparation step of optimization algorithm failed", VS_VISIBLE },
00273 { RET_OPTALG_SOLVE_FAILED,                                              "Problem could not be solved with given optimization algorithm", VS_VISIBLE },
00274 { RET_REALTIME_NO_INITIAL_VALUE,                                "No initial value has been specified", VS_VISIBLE },
00275 
00276 /* INTEGRATION_ALGORITHM: */
00277 { RET_INTALG_INIT_FAILED,                                               "Initialization of integration algorithm failed", VS_VISIBLE },
00278 { RET_INTALG_INTEGRATION_FAILED,                                "Integration algorithm failed to integrate dynamic system", VS_VISIBLE },
00279 { RET_INTALG_NOT_READY,                                                 "Integration algorithm has not been initialized", VS_VISIBLE },
00280 
00281 /* PLOT WINDOW */
00282 { RET_PLOT_WINDOW_CAN_NOT_BE_OPEN,                              "ACADO was not able to open the plot window", VS_VISIBLE },
00283 
00284 /* NLP SOLVER */
00285 { CONVERGENCE_ACHIEVED,                                                 "Convergence achieved", VS_VISIBLE },
00286 { CONVERGENCE_NOT_YET_ACHIEVED,                                 "Convergence not yet achieved", VS_VISIBLE },
00287 { RET_NLP_INIT_FAILED,                                                  "Initialization of NLP solver failed", VS_VISIBLE },
00288 { RET_NLP_STEP_FAILED,                                                  "Step of NLP solver failed", VS_VISIBLE },
00289 { RET_NLP_SOLUTION_FAILED,                                              "NLP solution failed", VS_VISIBLE },
00290 { RET_INITIALIZE_FIRST,                                                 "Object needs to be initialized first", VS_VISIBLE },
00291 { RET_SOLVER_NOT_SUTIABLE_FOR_REAL_TIME_MODE,   "The specified NLP solver is not designed for a real-time mode", VS_VISIBLE },
00292 { RET_ILLFORMED_HESSIAN_MATRIX,                                 "Hessian matrix is too ill-conditioned to continue", VS_VISIBLE },
00293 { RET_NONSYMMETRIC_HESSIAN_MATRIX,                              "Hessian matrix is not symmetric, proceeding with symmetrized Hessian", VS_VISIBLE },
00294 { RET_UNABLE_TO_EVALUATE_OBJECTIVE,                             "Evaluation of objective function failed", VS_VISIBLE },
00295 { RET_UNABLE_TO_EVALUATE_CONSTRAINTS,                   "Evaluation of constraints failed", VS_VISIBLE },
00296 { 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 },
00297 { 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 },
00298 
00299 /* CONIC SOLVER */
00300 { RET_CONIC_PROGRAM_INFEASIBLE,                                 "The optimization problem is infeasible", VS_VISIBLE },
00301 { RET_CONIC_PROGRAM_SOLUTION_FAILED,                    "Conic Program solution failed. The optimization problem might be infeasible", VS_VISIBLE },
00302 { RET_CONIC_PROGRAM_NOT_SOLVED,                                 "The Conic Program has not been solved successfully", VS_VISIBLE },
00303 
00304 /* CP SOLVER */
00305 { RET_UNABLE_TO_CONDENSE,                                               "Unable to condense banded CP", VS_VISIBLE },
00306 { RET_UNABLE_TO_EXPAND,                                                 "Unable to expand condensed CP", VS_VISIBLE },
00307 { RET_NEED_TO_CONDENSE_FIRST,                                   "Condensing cannot be frozen as banded CP needs to be condensed first", VS_VISIBLE },
00308 { RET_BANDED_CP_INIT_FAILED,                                    "Initialization of banded CP solver failed", VS_VISIBLE },
00309 { RET_BANDED_CP_SOLUTION_FAILED,                                "Solution of banded CP failed", VS_VISIBLE },
00310 
00311 /* OCP */
00312 { RET_TRANSITION_NOT_DEFINED,                                   "No transition function found", VS_VISIBLE },
00313 
00314 /* QP SOLVER */
00315 { RET_QP_INIT_FAILED,                                                   "QP initialization failed", VS_VISIBLE },
00316 { RET_QP_SOLUTION_FAILED,                                               "QP solution failed", VS_VISIBLE },
00317 { RET_QP_SOLUTION_REACHED_LIMIT,                                "QP solution stopped as iteration limit is reached", VS_VISIBLE },
00318 { RET_QP_INFEASIBLE,                                                    "QP solution failed due to infeasibility", VS_VISIBLE },
00319 { RET_QP_UNBOUNDED,                                                             "QP solution failed due to unboundedness", VS_VISIBLE },
00320 { RET_QP_NOT_SOLVED,                                                    "QP has not been solved", VS_VISIBLE },
00321 { RET_RELAXING_QP,                                                              "QP needs to be relaxed due to infeasibility", VS_VISIBLE },
00322 { RET_COULD_NOT_RELAX_QP,                                               "QP could not be relaxed", VS_VISIBLE },
00323 { RET_QP_SOLVER_CAN_ONLY_SOLVE_QP,                              "The QP solver can not deal with general conic problems.", VS_VISIBLE },
00324 { RET_QP_HAS_INCONSISTENT_BOUNDS,                               "QP cannot be solved due to inconsistent bounds", VS_VISIBLE },
00325 { RET_UNABLE_TO_HOTSTART_QP,                                    "Unable to hotstart QP with given solver", VS_VISIBLE },
00326 
00327 /* MPC SOLVER */
00328 { RET_NONPOSITIVE_WEIGHT,                                               "Weighting matrices must be positive definite", VS_VISIBLE },
00329 { RET_INITIAL_CHOLESKY_FAILED,                                  "Setting up initial Cholesky decompostion failed", VS_VISIBLE },
00330 { RET_HOMOTOPY_STEP_FAILED,                                             "Unable to perform homotopy step", VS_VISIBLE },
00331 { RET_STEPDIRECTION_DETERMINATION_FAILED,               "Determination of step direction failed", VS_VISIBLE },
00332 { RET_STEPDIRECTION_FAILED_CHOLESKY,                    "Abnormal termination due to Cholesky factorisation", VS_VISIBLE },
00333 { RET_STEPLENGTH_DETERMINATION_FAILED,                  "Determination of step direction failed", VS_VISIBLE },
00334 { RET_OPTIMAL_SOLUTION_FOUND,                                   "Optimal solution of neighbouring QP found", VS_VISIBLE },
00335 { RET_MAX_NWSR_REACHED,                                                 "Maximum number of working set recalculations performed", VS_VISIBLE },
00336 { RET_MATRIX_NOT_SPD,                                                   "DMatrix not positive definite", VS_VISIBLE },
00337 
00338 /* CODE EXPORT */
00339 { RET_CODE_EXPORT_SUCCESSFUL,                                   "Code generation successful", VS_VISIBLE },
00340 { RET_UNABLE_TO_EXPORT_CODE,                                    "Unable to generate code", VS_VISIBLE },
00341 { RET_INVALID_OBJECTIVE_FOR_CODE_EXPORT,                "Only standard LSQ objective supported for code generation", VS_VISIBLE },
00342 { RET_NO_DISCRETE_ODE_FOR_CODE_EXPORT,                  "No discrete-time ODEs supported for code generation", VS_VISIBLE },
00343 { RET_ONLY_ODE_FOR_CODE_EXPORT,                                 "Only ODEs supported for code generation", VS_VISIBLE },
00344 { RET_ONLY_STATES_AND_CONTROLS_FOR_CODE_EXPORT, "No parameters, disturbances or algebraic states supported for code generation", VS_VISIBLE },
00345 { RET_ONLY_EQUIDISTANT_GRID_FOR_CODE_EXPORT,    "Only equidistant evaluation grids supported for code generation", VS_VISIBLE },
00346 { RET_ONLY_BOUNDS_FOR_CODE_EXPORT,                              "Only state and control bounds supported for code generation", VS_VISIBLE },
00347 { RET_QPOASES_EMBEDDED_NOT_FOUND,                               "Embedded qpOASES code not found", VS_VISIBLE },
00348 { RET_UNABLE_TO_EXPORT_STATEMENT,                               "Unable to export statement due to incomplete definition", VS_VISIBLE },
00349 { RET_INVALID_CALL_TO_EXPORTED_FUNCTION,                "Invalid call to export functions (check number of calling arguments)", VS_VISIBLE },
00350 
00351 /* IMPORTANT: Terminal list element! */
00352 { TERMINAL_LIST_ELEMENT,                                                " ", VS_HIDDEN }
00353 };
00354 
00355 
00356 //
00357 // HELPER FUNCTIONS:
00358 //
00359 
00360 
00361 // Converts returnValueLevel enum type to a const char*
00362 const char* returnValueLevelToString(returnValueLevel level)
00363 {
00364         switch ( level )
00365         {
00366         case LVL_DEBUG:
00367                 return COL_DEBUG"Debug";
00368 
00369         case LVL_FATAL:
00370                 return COL_FATAL"Fatal error";
00371 
00372         case LVL_ERROR:
00373                 return COL_ERROR"Error";
00374 
00375         case LVL_WARNING:
00376                 return COL_WARNING"Warning";
00377 
00378         case LVL_INFO:
00379                 return COL_INFO"Information";
00380         }
00381 
00382         return 0;
00383 }
00384 
00385 // Converts returnValueType enum type to a const char*
00386 const char* returnValueTypeToString(returnValueType type) {
00387         ReturnValueList* p = returnValueList;
00388         while( (p->key != type) && (p->key != TERMINAL_LIST_ELEMENT) ) p++;
00389         return p->data;
00390 }
00391 
00395 class returnValue::returnValueData
00396 {
00397 public:
00398         returnValue* owner;
00399         std::vector<const char*> messages;
00400 };
00401 
00402 //
00403 // PUBLIC MEMBER FUNCTIONS:
00404 //
00405 
00406 
00407 /* Constructor used by the ACADOERROR and similar macros.
00408  *
00409  */
00410 returnValue::returnValue(const char* msg, returnValueLevel _level, returnValueType _type) {
00411         data = new returnValueData();
00412         data->owner = this;
00413         data->messages.push_back(msg);
00414         status = STATUS_UNHANDLED;
00415         type = _type;
00416         level = _level;
00417 }
00418 
00419 /* Construct default returnValue.
00420  *
00421  */
00422 returnValue::returnValue() : data(0) {}
00423 
00424 /* Construct returnValue only from typedef.
00425  *
00426  */
00427 returnValue::returnValue(returnValueType _type) : type(_type), level(LVL_ERROR), status(STATUS_UNHANDLED), data(0) {}
00428 
00429 /* Construct returnValue from int, for compatibility
00430  *
00431  */
00432 returnValue::returnValue(int _type) : level(LVL_ERROR), status(STATUS_UNHANDLED), data(0) {
00433         type = returnValueType(_type);
00434 }
00435 
00436 /* Copy constructor with minimum performance cost.
00437  *  Newly constructed instance takes ownership of data.
00438  */
00439 returnValue::returnValue(const returnValue& old) {
00440         // Copy data
00441         if (old.data) {
00442                 data = old.data;
00443                 data->owner = this;
00444         } else {
00445                 data = 0;
00446         }
00447         // Copy details
00448         type = old.type;
00449         level = old.level;
00450         status = old.status;
00451 }
00452 
00453 returnValueLevel returnValue::getLevel() const {
00454         return level;
00455 }
00456 
00457 /* Compares the returnValue type to its enum
00458  *
00459  */
00460 bool returnValue::operator!=(returnValueType cmp_type) const {
00461         return type != cmp_type;
00462 }
00463 
00464 /* Compares the returnValue type to its enum
00465  *
00466  */
00467 bool returnValue::operator==(returnValueType cmp_type) const {
00468         return type == cmp_type;
00469 }
00470 
00471 /* Returns true if return value type is not SUCCESSFUL_RETURN
00472  *
00473  */
00474 bool returnValue::operator!() const {
00475         return type != SUCCESSFUL_RETURN;
00476 }
00477 
00478 /*  Assignment operator.
00479  *  Left hand side instance takes ownership of data.
00480  */
00481 returnValue& returnValue::operator=(const returnValue& old) {
00482         // Clean up data if already existing
00483         if (data && (data->owner == this)) delete data;
00484 
00485         // Copy data
00486         if (old.data) {
00487                 data = old.data;
00488                 data->owner = this;
00489         } else {
00490                 data = 0;
00491         }
00492         // Copy details
00493         type = old.type;
00494         level = old.level;
00495         status = old.status;
00496 
00497         return *this;
00498 }
00499 
00500 /* Compatibility function, allows returnValue to be used as a number, similar to a enum.
00501  *
00502  */
00503 returnValue::operator int() {
00504         return type;
00505 }
00506 
00507 /* Destroys data instance only if it owns it
00508  *
00509  */
00510 returnValue::~returnValue() {
00511         if ( data )
00512         {
00513                 if (data->owner == this)
00514                 {
00515                         // If is not succesful and was not handled yet, by default print message to standard output
00516                         if (status != STATUS_HANDLED)
00517                         {
00518                                 print();
00519                         }
00520                 
00521                         if ( data )
00522                         {
00523                                 delete data;
00524                         }
00525 
00526 #ifdef ACADO_WITH_TESTING
00527                         if (level == LVL_FATAL || level == LVL_ERROR || level == LVL_WARNING)
00528 #else
00529                         if (level == LVL_FATAL)
00530 #endif
00531                         {
00532                                 abort();
00533                         }
00534                 }
00535         }
00536 }
00537 
00538 /* Constructor used by the ACADOERROR and similar macros. Special case.
00539  * Constructs returnValue from old one, changing level and adding message
00540  */
00541 returnValue::returnValue(const char* msg, returnValueLevel _level, const returnValue& old) {
00542         if (old.data) {
00543                 data = old.data;
00544                 data->owner = this;
00545                 data->messages.push_back(msg);
00546         }
00547         status = STATUS_UNHANDLED;
00548         level = _level;
00549         type = old.type;
00550 }
00551 
00552 /* Adds another message to the end of messages list.
00553  *
00554  */     
00555 returnValue& returnValue::addMessage(const char* msg) {
00556         if (!data) {
00557                 data = new returnValueData();
00558                 data->owner = this;
00559         }
00560         data->messages.push_back(msg);
00561         return *this;
00562 }
00563 
00564 /* Change the importance level of the returned value
00565  *
00566  */
00567 returnValue& returnValue::changeLevel(returnValueLevel _level) {
00568         level = _level;
00569         return *this;
00570 }
00571 
00572 /* Change the type of the returned message
00573  *
00574  */
00575 returnValue& returnValue::changeType(returnValueType _type) {
00576 
00577         type = _type;
00578         return *this;
00579 }
00580 
00581 /* Prints all messages to the standard output.
00582  *
00583  */     
00584 void returnValue::print() {
00585 
00586         cout    << COL_INFO"[ACADO] " << returnValueLevelToString( level )
00587                         << ": " << returnValueTypeToString( type ) << COL_INFO << endl;
00588 
00589         if ( data )
00590                 for (vector<const char*>::iterator it = data->messages.begin(); it != data->messages.end(); it++)
00591                         cout << "  " << (*it) << endl;
00592         cout << endl;
00593 
00594         status = STATUS_HANDLED;
00595 }
00596 
00597 /* Prints only the most basic information, no messages, to the standard output.
00598  *
00599  */
00600 void returnValue::printBasic() {
00601 
00602         std::cout << returnValueLevelToString(level) << ": " << returnValueTypeToString(type) << std::endl; 
00603         status = STATUS_HANDLED;
00604 }
00605 
00606 // Logging class
00607 
00608 ostream& Logger::get(returnValueLevel level)
00609 {
00610         cout << COL_INFO"[ACADO] " << returnValueLevelToString( level ) << ": " << COL_INFO;
00611 
00612         return cout;
00613 }
00614 
00615 CLOSE_NAMESPACE_ACADO
00616 
00617 
00618 /*
00619  *      end of file
00620  */


acado
Author(s): Milan Vukov, Rien Quirynen
autogenerated on Thu Aug 27 2015 11:57:48