interfaces/matlab/examples/mexfiles/simple_mpc.cpp
Go to the documentation of this file.
1 
35 #include <acado_toolkit.hpp> // Include the ACADO toolkit
36 #include <acado/utils/matlab_acado_utils.hpp> // Include specific Matlab utils
37 
38 USING_NAMESPACE_ACADO // Open the namespace
39 
40 void mexFunction( int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[] ) // Start the MEX function. Do NOT change the header of this function.
41  {
42  clearAllStaticCounters( ); // Clear software counters
43 
44 
45 
46  // INTRODUCE THE VARIABLES:
47  // -------------------------
52 
53  Control R;
54  Control F;
55 
56  double mB = 350.0;
57  double mW = 50.0;
58  double kS = 20000.0;
59  double kT = 200000.0;
60 
61 
62  // DEFINE A DIFFERENTIAL EQUATION:
63  // -------------------------------
65 
66  f << dot(xB) == vB;
67  f << dot(xW) == vW;
68  f << dot(vB) == ( -kS*xB + kS*xW + F ) / mB;
69  f << dot(vW) == ( -kT*xB - (kT+kS)*xW + kT*R - F ) / mW;
70 
71 
72  // DEFINE LEAST SQUARE FUNCTION:
73  // -----------------------------
74  Function h;
75 
76  h << xB;
77  h << xW;
78  h << vB;
79  h << vW;
80 
81  Matrix Q(4,4);
82  Q.setIdentity();
83  Q(0,0) = 10.0;
84  Q(1,1) = 10.0;
85 
86  Vector r(4);
87  r.setAll( 0.0 );
88 
89 
90  // DEFINE AN OPTIMAL CONTROL PROBLEM:
91  // ----------------------------------
92  const double t_start = 0.0;
93  const double t_end = 1.0;
94 
95  OCP ocp( t_start, t_end, 20 );
96 
97  ocp.minimizeLSQ( Q, h, r );
98 
99  ocp.subjectTo( f );
100 
101  ocp.subjectTo( -500.0 <= F <= 500.0 );
102  ocp.subjectTo( R == 0.0 );
103 
104 
105 
106  // SETTING UP THE (SIMULATED) PROCESS:
107  // -----------------------------------
108  OutputFcn identity;
109  DynamicSystem dynamicSystem( f,identity );
110 
111  Process process( dynamicSystem,INT_RK45 );
112 
113  VariablesGrid disturbance = readFromFile( "simple_mpc_road.txt" );
114  process.setProcessDisturbance( disturbance );
115 
116 
117  // SETTING UP THE MPC CONTROLLER:
118  // ------------------------------
119  RealTimeAlgorithm alg( ocp,0.05 );
120  alg.set( MAX_NUM_ITERATIONS, 2 );
121 
122  StaticReferenceTrajectory zeroReference;
123 
124  Controller controller( alg,zeroReference );
125 
126 
127  // SETTING UP THE SIMULATION ENVIRONMENT, RUN THE EXAMPLE...
128  // ----------------------------------------------------------
129  SimulationEnvironment sim( 0.0,3.0,process,controller );
130 
131  Vector x0(4);
132  x0(0) = 0.01;
133  x0(1) = 0.0;
134  x0(2) = 0.0;
135  x0(3) = 0.0;
136 
137  sim.init( x0 );
138  sim.run( );
139 
140 
141  // ...AND PLOT THE RESULTS
142  // ----------------------------------------------------------
143  VariablesGrid sampledProcessOutput;
144  sim.getSampledProcessOutput( sampledProcessOutput );
145  acadoPlot(sampledProcessOutput);
146 
147  VariablesGrid feedbackControl;
148  sim.getFeedbackControl( feedbackControl );
149  acadoPlot(feedbackControl);
150 
151 
152 
153  clearAllStaticCounters( ); // Clear software counters
154 }
155 
Calculates the control inputs of the Process based on the Process outputs.
Definition: controller.hpp:71
Allows to setup and evaluate a general function based on SymbolicExpressions.
Definition: function_.hpp:59
void acadoPlot(VariablesGrid grid)
Allows to setup and evaluate output functions based on SymbolicExpressions.
Definition: output_fcn.hpp:55
Stores a DifferentialEquation together with an OutputFcn.
#define USING_NAMESPACE_ACADO
Provides a time grid consisting of vector-valued optimization variables at each grid point...
USING_NAMESPACE_ACADO void mexFunction(int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[])
returnValue getFeedbackControl(Curve &_feedbackControl) const
User-interface to formulate and solve model predictive control problems.
returnValue subjectTo(const DifferentialEquation &differentialEquation_)
Definition: ocp.cpp:153
returnValue readFromFile(real_t *data, int nrow, int ncol, const char *datafilename)
returnValue getSampledProcessOutput(VariablesGrid &_sampledProcessOutput)
returnValue set(OptionsName name, int value)
Definition: options.cpp:126
returnValue minimizeLSQ(const DMatrix &S, const Function &h, const DVector &r)
Definition: ocp.cpp:244
returnValue init(const DVector &x0_, const DVector &p_=emptyConstVector)
Abstract base class for interfacing tailored matrix-vector operations.
Data class for defining optimal control problems.
Definition: ocp.hpp:89
Allows to define a static reference trajectory that the ControlLaw aims to track. ...
Expression dot(const Expression &arg)
returnValue clearAllStaticCounters()
const double t_end
returnValue setProcessDisturbance(const Curve &_processDisturbance)
Definition: process.cpp:289
const double t_start
Allows to run closed-loop simulations of dynamic systems.
Simulates the process to be controlled based on a dynamic model.
Definition: process.hpp:71
#define R
Allows to setup and evaluate differential equations (ODEs and DAEs) based on SymbolicExpressions.


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