acado_types.hpp
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 
34 #ifndef ACADO_TOOLKIT_ACADO_TYPES_HPP
35 #define ACADO_TOOLKIT_ACADO_TYPES_HPP
36 
38 
40 
42 typedef unsigned int uint;
43 
45 typedef bool BooleanType;
47 #define BT_TRUE true
48 
49 #define BT_FALSE false
50 
51 #define YES true
52 
53 #define NO false
54 
56 typedef void (*cFcnPtr)( double* x, double* f, void *userData );
57 
59 typedef void (*cFcnDPtr)( int number, double* x, double* seed, double* f, double* df, void *userData );
60 
65 
69 };
70 
73 
92 };
93 
96 
111 };
112 
113 
117 {
121 };
122 
123 
124 
127 
132 };
133 
134 
137 
141 };
142 
143 
146 
154 };
155 
156 
159 
161  IFT,
164 };
165 
166 
169 
175 };
176 
177 
180 
187 };
188 
189 
191 
195 };
196 
197 
198 
201 
206 };
207 
208 
211 
217 };
218 
219 
222 {
226 };
227 
228 
231 {
237 };
238 
239 
244 
252 };
253 
254 
257 
266 };
267 
268 
272 
275 };
276 
277 
281 
285 };
286 
287 
288 
293 {
295  LOW,
301 };
302 
304 
308 };
309 
310 
314 
318 };
319 
320 
324 {
328 };
329 
330 
332 {
345 // LIFTED_INTEGRATOR_MODE, /**< This determines the mode of lifting of the implicit integrator. */
427 };
428 
429 
433 {
435  // 1
445  // 10
456  // 20
471  // 30
482  // 40
493  // 50
495 };
496 
497 
499 {
505 };
506 
507 
509 {
511  // 1
512 // PLOT_DIFFERENTIAL_STATES,
513 // PLOT_ALGEBRAIC_STATES,
514 // PLOT_CONTROLS,
515 // PLOT_PARAMETERS,
516 // PLOT_DISTURBANCES,
517 // PLOT_INTERMEDIATE_STATES,
523 };
524 
525 
527 {
530 };
531 
532 
536 {
541 };
542 
543 
544 
548 {
552 };
553 
554 
555 
559 {
569 };
570 
571 
575 {
580 };
581 
582 
585 
590 };
591 
592 
595 
598 };
599 
600 
603 {
606 };
607 
608 
609 
612 
614  // 1
621 };
622 
623 
624 
627 
628  BLOCK_REG, // = 0
630 };
631 
632 
634 {
642 };
643 
644 
647 
652 };
653 
654 
655 
659 {
665 };
666 
667 
670 {
681 };
682 
683 
686 {
691 };
692 
693 
696 {
706 };
707 
708 
711 {
716 };
717 
718 
721 {
725 };
726 
727 
730 {
734 };
735 
736 
740 
749 };
750 
751 
752 
756 {
764 };
765 
766 
767 
771 {
782 };
783 
784 
786 {
790 };
791 
792 
794 {
800 };
801 
803 {
813 };
814 
816 {
820 };
821 
833 {
835 /* miscellaneous */
857 /* IO utils: */
865 /* DMatrix/DVector */
875 /* Sparse Solver */
878 /* Grid */
885 /* Options */
891 /* Plotting */
897 /* Logging */
902 /* SimulationEnvironment */
911 /* Block */
914 /* Time */
918 /* Process */
928 /* Actuator / Sensor */
940 /* Noise */
945 /* Controller */
952 /* DynamicControlUnit / Estimator / Optimizer */
962 /* ControlLaw */
968 /* RealTimeAlgorithm */
971 /* OutputTransformator */
975 /* Function */
982 /* Expression */
989 /* Modeling Tools */
994 /* OBJECTIVE */
998 /* Integrator */
1021 /* DynamicDiscretization */
1027 /* OPTIMIZATION_ALGORITHM: */
1039 /* INTEGRATION_ALGORITHM: */
1044 /* PLOT WINDOW */
1047 /* NLP SOLVER */
1062 /* CONIC SOLVER */
1067 /* CP SOLVER */
1074 /* OCP */
1077 /* QP SOLVER */
1090 /* MPC SOLVER */
1101 /* CODE EXPORT */
1115 /* EXPORTED INTEGRATORS */
1117 };
1118 
1121 {
1127 };
1128 
1140 {
1141 public:
1142 
1146  returnValue();
1147 
1152 
1156  returnValue(int _type);
1157 
1161  returnValue(const returnValue& old);
1162 
1167 
1171  returnValue(const char* msg, returnValueLevel level,const returnValue& old);
1172 
1176  returnValue& addMessage(const char* msg);
1177 
1182 
1187 
1188  returnValueLevel getLevel() const;
1189 
1193  void print();
1194 
1198  void printBasic();
1199 
1203  ~returnValue();
1204 
1208  bool operator!=(returnValueType cmp_type) const;
1209 
1213  bool operator==(returnValueType cmp_type) const;
1214 
1218  bool operator!() const;
1219 
1223  returnValue& operator=(const returnValue& old);
1224 
1228  operator int();
1229 
1230 private:
1233  int status;
1234 
1237 };
1238 
1240 
1241 #endif // ACADO_TOOLKIT_ACADO_TYPES_HPP
1242 
1243 /*
1244  * end of file
1245  */
OperatorName
Definition: acado_types.hpp:72
StateDiscretizationType
Returned value is a information.
Lowest level, the debug level.
HessianApproximationMode
ControlParameterizationType
bool operator!() const
returnValue & addMessage(const char *msg)
returnValueLevel getLevel() const
ParetoFrontGeneration
SparseQPsolutionMethods
returnValue & changeLevel(returnValueLevel level)
LinearAlgebraSolver
BlockStatus
CondensingStatus
bool BooleanType
Definition: acado_types.hpp:45
PlotMode
Allows to pass back messages to the calling function.
HessianRegularizationMode
ProcessSimulationAlgorithm
StateOfAggregation
BEGIN_NAMESPACE_ACADO typedef unsigned int uint
Definition: acado_types.hpp:42
BlockName
Returned value is a error.
ImplicitIntegratorMode
TimeHorizonElement
#define CLOSE_NAMESPACE_ACADO
void(* cFcnDPtr)(int number, double *x, double *seed, double *f, double *df, void *userData)
Definition: acado_types.hpp:59
ConicSolverStatus
VariableType
Definition: acado_types.hpp:95
AlgebraicRelaxationType
PlotFrequency
ClockStatus
returnValueType
Defines all symbols for global return values.
Returned value is a warning.
LogPrintMode
bool operator==(returnValueType cmp_type) const
ExportStruct
PlotName
IntegratorType
returnValueLevel
GlobalizationStrategy
LogRecordItemType
PlotFormat
UnrollOption
PrintScheme
ExportStatementOperator
Returned value is a fatal error, assert like use, aborts execution is unhandled.
returnValue & operator=(const returnValue &old)
InfeasibleQPhandling
LogName
LogFrequency
ExportType
PrintLevel
DifferentialEquationType
SensitivityType
ProcessPlotName
bool operator!=(returnValueType cmp_type) const
NeutralElement
Definition: acado_types.hpp:64
QPStatus
returnValueLevel level
CondensingType
MonotonicityType
SubPlotType
returnValue & changeType(returnValueType type)
CurvatureType
#define BEGIN_NAMESPACE_ACADO
void(* cFcnPtr)(double *x, double *f, void *userData)
Definition: acado_types.hpp:56
SubBlockMatrixType
MergeMethod
MeasurementGrid
CondensedHessianCholeskyDecomposition
returnValueData * data
QPSolverName
returnValueType type
OptionsName
OperatingSystem
InterpolationMode


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