-
Notifications
You must be signed in to change notification settings - Fork 1
Expand file tree
/
Copy pathMPC_Validator.c
More file actions
241 lines (200 loc) · 8.07 KB
/
MPC_Validator.c
File metadata and controls
241 lines (200 loc) · 8.07 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
/*
* MPC_Validator.c: an oversight s-function to check the status code
* returned from the MPC calculation process to make sure that the
* steering command received was calculated properly.
*
*/
#define S_FUNCTION_NAME MPC_Validator
#define S_FUNCTION_LEVEL 2
/*
* Need to include simstruc.h for the definition of the SimStruct and
* its associated macro definitions.
*/
#include "simstruc.h"
/* Error handling
* --------------
*
* You should use the following technique to report errors encountered within
* an S-function:
*
* ssSetErrorStatus(S,"Error encountered due to ...");
* return;
*
* Note that the 2nd argument to ssSetErrorStatus must be persistent memory.
* It cannot be a local variable. For example the following will cause
* unpredictable errors:
*
* mdlOutputs()
* {
* char msg[256]; {ILLEGAL: to fix use "static char msg[256];"}
* sprintf(msg,"Error due to %s", string);
* ssSetErrorStatus(S,msg);
* return;
* }
*
* See matlabroot/simulink/src/sfuntmpl_doc.c for more details.
*/
/*====================*
* S-function methods *
*====================*/
/* Function: mdlInitializeSizes ===============================================
* Abstract:
* The sizes information is used by Simulink to determine the S-function
* block's characteristics (number of inputs, outputs, states, etc.).
*/
static void mdlInitializeSizes(SimStruct *S)
{
ssSetNumSFcnParams(S, 0); /* Number of expected parameters */
if (ssGetNumSFcnParams(S) != ssGetSFcnParamsCount(S)) {
/* Return if number of expected != number of actual parameters */
return;
}
// Not using any states since this s-function just processes current data
ssSetNumContStates(S, 0);
ssSetNumDiscStates(S, 0);
if (!ssSetNumInputPorts(S, 3)) return;
ssSetInputPortWidth(S, 0, 1);
ssSetInputPortWidth(S, 1, 1);
ssSetInputPortWidth(S, 2, 1);
ssSetInputPortDataType(S, 0, DYNAMICALLY_TYPED);
ssSetInputPortDataType(S, 1, DYNAMICALLY_TYPED);
ssSetInputPortDataType(S, 2, DYNAMICALLY_TYPED);
ssSetInputPortRequiredContiguous(S, 0, true); /*direct input signal access*/
ssSetInputPortRequiredContiguous(S, 1, true); /*direct input signal access*/
ssSetInputPortRequiredContiguous(S, 2, true); /*direct input signal access*/
/*
* Set direct feedthrough flag (1=yes, 0=no).
* A port has direct feedthrough if the input is used in either
* the mdlOutputs or mdlGetTimeOfNextVarHit functions.
* See matlabroot/simulink/src/sfuntmpl_directfeed.txt.
*/
ssSetInputPortDirectFeedThrough(S, 0, 1);
ssSetInputPortDirectFeedThrough(S, 1, 1);
if (!ssSetNumOutputPorts(S, 1)) return;
ssSetOutputPortWidth(S, 0, 1);
ssSetNumSampleTimes(S, 1);
ssSetNumRWork(S, 0);
ssSetNumIWork(S, 0);
ssSetNumPWork(S, 0);
ssSetNumModes(S, 0);
ssSetNumNonsampledZCs(S, 0);
ssSetOptions(S, 0);
}
/* Function: mdlInitializeSampleTimes =========================================
* Abstract:
* This function is used to specify the sample time(s) for your
* S-function. You must register the same number of sample times as
* specified in ssSetNumSampleTimes.
*/
static void mdlInitializeSampleTimes(SimStruct *S)
{
ssSetSampleTime(S, 0, INHERITED_SAMPLE_TIME);
ssSetOffsetTime(S, 0, 0.0);
}
#define MDL_INITIALIZE_CONDITIONS /* Change to #undef to remove function */
#if defined(MDL_INITIALIZE_CONDITIONS)
/* Function: mdlInitializeConditions ========================================
* Abstract:
* In this function, you should initialize the continuous and discrete
* states for your S-function block. The initial states are placed
* in the state vector, ssGetContStates(S) or ssGetRealDiscStates(S).
* You can also perform any other initialization activities that your
* S-function may require. Note, this routine will be called at the
* start of simulation and if it is present in an enabled subsystem
* configured to reset states, it will be call when the enabled subsystem
* restarts execution to reset the states.
*/
static void mdlInitializeConditions(SimStruct *S)
{
}
#endif /* MDL_INITIALIZE_CONDITIONS */
#define MDL_START /* Change to #undef to remove function */
#if defined(MDL_START)
/* Function: mdlStart =======================================================
* Abstract:
* This function is called once at start of model execution. If you
* have states that should be initialized once, this is the place
* to do it.
*/
static void mdlStart(SimStruct *S)
{
}
#endif /* MDL_START */
/* Function: mdlOutputs =======================================================
* Abstract:
* In this function, you compute the outputs of your S-function
* block.
*/
static void mdlOutputs(SimStruct *S, int_T tid)
{
const uint32_T *delta = (const uint32_T*) ssGetInputPortSignal(S,0);
const int8_T *status = (const int8_T*) ssGetInputPortSignal(S,1);
const uint16_T *cycle = (const uint16_T*) ssGetInputPortSignal(S,2);
real_T *y = ssGetOutputPortSignal(S,0);
float deltaWork;
/* Here is where the meat of this s-function gets done. First we check
* the status flag, then we convert the steering command, then finally
* we check the command and output it to the vehicle. */
if(*status != -1)
{
/* We got to here, so the solver at least thinks that it produced
* a reasonable solution. Now we need to convert the steering
* command back to a double, and we'll check it out too. */
/* We'll use memcpy to do a straight transfer of bits from the
* uint32 type to a single precision variable. Later we'll turn
* it into a double so that Simulink can be happy with it */
memcpy(&deltaWork,delta,sizeof(double));
y[0] = (double)deltaWork;
y[1] = y[0];
}
else
{
/* The "we're screwed" case where the solver didn't find a
* feasible solution to the problem. Need to figure out what the
* backup plan is. */
}
}
#define MDL_UPDATE /* Change to #undef to remove function */
#if defined(MDL_UPDATE)
/* Function: mdlUpdate ======================================================
* Abstract:
* This function is called once for every major integration time step.
* Discrete states are typically updated here, but this function is useful
* for performing any tasks that should only take place once per
* integration step.
*/
static void mdlUpdate(SimStruct *S, int_T tid)
{
}
#endif /* MDL_UPDATE */
#define MDL_DERIVATIVES /* Change to #undef to remove function */
#if defined(MDL_DERIVATIVES)
/* Function: mdlDerivatives =================================================
* Abstract:
* In this function, you compute the S-function block's derivatives.
* The derivatives are placed in the derivative vector, ssGetdX(S).
*/
static void mdlDerivatives(SimStruct *S)
{
}
#endif /* MDL_DERIVATIVES */
/* Function: mdlTerminate =====================================================
* Abstract:
* In this function, you should perform any actions that are necessary
* at the termination of a simulation. For example, if memory was
* allocated in mdlStart, this is the place to free it.
*/
static void mdlTerminate(SimStruct *S)
{
}
/*======================================================*
* See sfuntmpl_doc.c for the optional S-function methods *
*======================================================*/
/*=============================*
* Required S-function trailer *
*=============================*/
#ifdef MATLAB_MEX_FILE /* Is this file being compiled as a MEX-file? */
#include "simulink.c" /* MEX-file interface mechanism */
#else
#include "cg_sfun.h" /* Code generation registration function */
#endif