]> rtime.felk.cvut.cz Git - socketcan-simulink.git/blob - blocks/header.c
Clone robotic arm control model for Raspberry Pi build.
[socketcan-simulink.git] / blocks / header.c
1 /* Copyright (C) 2013 Czech Technical University in Prague
2  *
3  * Authors:
4  *     - Carlos Jenkins <carlos@jenkins.co.cr>
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are
8  * met:
9  *
10  * 1. Redistributions of source code must retain the above copyright
11  *    notice, this list of conditions and the following disclaimer.
12  *
13  * 2. Redistributions in binary form must reproduce the above copyright
14  *    notice, this list of conditions and the following disclaimer in the
15  *    documentation and/or other materials provided with the
16  *    distribution.
17  *
18  * 3. Neither the name of the copyright holder nor the names of its
19  *    contributors may be used to endorse or promote products derived
20  *    from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
25  * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
26  * HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
27  * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
28  * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
29  * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
30  * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
31  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
32  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
33  *
34  * File : header.c
35  * Abstract:
36  *     Common header for all RPP S-Functions.
37  *     This file should be included at the beginning of a C-MEX S-Function block
38  *     implementation after defining S_FUNCTION_NAME. It include refactored and
39  *     commonly repeated structures that pollute S-Functions implementations
40  *     (in conjunction with trailer.c). This file include basic includes,
41  *     required definitions, macro definitions and documentation and commented
42  *     prototypes for optional model calls/hooks.
43  *
44  * References:
45  *     mdlInitializeSizes()       : sfunctions.pdf p. 441 [Required]
46  *     mdlInitializeSampleTimes() : sfunctions.pdf p. 436 [Required]
47  *     mdlOutputs()               : sfunctions.pdf p. 447 [Required]
48  *     mdlTerminate()             : sfunctions.pdf p. 493 [Required]
49  *
50  *                          .: S-Function callback methods :.
51  *
52  *                              ***********************
53  *                              * Start of simulation *
54  *                              ***********************
55  *                                         |
56  *                        _               \_/
57  *                       |      +--------------------+
58  *                       |      | mdlInitializeSizes |
59  *                       |      +--------------------+
60  *      Initialization  -|                 |
61  *                       |                \_/
62  *                       |   +--------------------------+
63  *                       |   | mdlInitializeSampleTimes |
64  *                       |_  +--------------------------+
65  *                                         |
66  *                        _______________\ |
67  *                       |               /\_/
68  *                       |          +------------+
69  *      Simulation loop -|          | mdlOutputs |
70  *                       |          +------------+
71  *                       |_________________|
72  *                                         |
73  *                                        \_/
74  *                                 +--------------+
75  *                                 | mdlTerminate |
76  *                                 +--------------+
77  *
78  *     mdlCheckParameters()       : sfunctions.pdf p. 421 [Optional]
79  *     mdlRTW()                   : sfunctions.pdf p. 458 [Optional]
80  *     mdlSetWorkWidths()         : sfunctions.pdf p. 489 [Optional]
81  *     mdlStart()                 : sfunctions.pdf p. 492 [Optional]
82  *
83  *     trailer.c
84  */
85
86
87 #ifndef S_FUNCTION_NAME
88 #error 'Please include this file inside an S-Function implementation.'
89 #endif
90
91 #define S_FUNCTION_LEVEL 2
92
93
94 /*
95  * Include C numerics library in order to use trunc() and other nice goodies.
96  */
97 #include <math.h>
98
99 /*
100  * Need to include simstruc.h for the definition of the SimStruct and
101  * its associated macro definitions.
102  */
103 #include "simstruc.h"
104 #define EDIT_OK(S, P_IDX) \
105  (!((ssGetSimMode(S)==SS_SIMMODE_SIZES_CALL_ONLY) && mxIsEmpty(ssGetSFcnParam(S, P_IDX))))
106 #define SAMPLE_TIME (ssGetSFcnParam(S, 1))
107
108
109 /* Function: isRealMatrix ======================================================
110  * Abstract:
111  *     Utility function to verify that the mxArray is a real (double) finite
112  *     matrix.
113  */
114 static bool isRealMatrix(const mxArray * const m)
115 {
116     if (mxIsNumeric(m) && mxIsDouble(m) && !mxIsLogical(m) && !mxIsComplex(m) &&
117        !mxIsSparse(m) && !mxIsEmpty(m) && mxGetNumberOfDimensions(m) == 2) {
118
119         const double * const data = mxGetPr(m);
120         const size_t numEl = mxGetNumberOfElements(m);
121         size_t i;
122
123         for (i = 0; i < numEl; i++) {
124             if (!mxIsFinite(data[i])) {
125                 return(false);
126             }
127         }
128
129         return(true);
130
131     } else {
132
133         return(false);
134
135     }
136 }
137
138
139 /* Function: checkSampleTime ===================================================
140  * Abstract:
141  *     Utility function to verify that sample time (for variable sample time
142  *     blocks) is valid.
143  */
144 static bool checkSampleTime(SimStruct* S, int paramNum)
145 {
146     if EDIT_OK(S, paramNum) {
147
148         const real_T* sampleTime = NULL;
149         const size_t stArraySize = mxGetM(SAMPLE_TIME) * mxGetN(SAMPLE_TIME);
150
151         /* Sample time must be a real scalar value or 2 element array. */
152         if (isRealMatrix(SAMPLE_TIME) &&
153            (stArraySize == 1 || stArraySize == 2)) {
154
155             sampleTime = (real_T*) mxGetPr(SAMPLE_TIME);
156
157         } else {
158             ssSetErrorStatus(S,
159                 "Invalid sample time. Sample time must be a "
160                 "real scalar value or an array of two real values.");
161             return false;
162         }
163
164         if (sampleTime[0] < 0.0 && sampleTime[0] != -1.0) {
165             ssSetErrorStatus(S,
166                 "Invalid sample time. Period must be non-negative or "
167                 "-1 (for inherited).");
168             return false;
169         }
170
171         if (stArraySize == 2 && sampleTime[0] > 0.0 &&
172            sampleTime[1] >= sampleTime[0]) {
173             ssSetErrorStatus(S,
174                 "Invalid sample time. Offset must be smaller than period.");
175             return false;
176         }
177
178         if (stArraySize == 2 && sampleTime[0] == -1.0 && sampleTime[1] != 0.0) {
179             ssSetErrorStatus(S,
180                 "Invalid sample time. When period is -1, offset must be 0.");
181             return false;
182         }
183
184         if (stArraySize == 2 && sampleTime[0] == 0.0 &&
185            !(sampleTime[1] == 1.0)) {
186             ssSetErrorStatus(S,
187                 "Invalid sample time. When period is 0, offset must be 1.");
188             return false;
189         }
190     }
191     return true;
192 }
193
194
195 /* Function: rppSetNumParams ===================================================
196  * Abstract:
197  *     Utility function to set the number of expected parameters, verify that
198  *     the number of expected parameters is equal to the number of parameters
199  *     entered in the dialog box return, and that the values entered are correct
200  *     (by calling S-Function specific mdlCheckParameters() function).
201  */
202 static void mdlCheckParameters(SimStruct* S);
203 static bool rppSetNumParams(SimStruct* S, int_T numParams)
204 {
205     ssSetNumSFcnParams(S, numParams);
206
207     #ifdef MATLAB_MEX_FILE
208     if (ssGetNumSFcnParams(S) == ssGetSFcnParamsCount(S)) {
209
210         mdlCheckParameters(S);
211         if (ssGetErrorStatus(S) != NULL) {
212             return false;
213         }
214     } else {
215         /* Return if number of expected != number of actual parameters */
216         return false;
217     }
218     #endif
219
220     /* Set the parameters tunable status */
221     int i;
222     for (i = 0; i < numParams; i++) {
223         ssSetSFcnParamTunable(S, i, false);
224     }
225
226     return true;
227 }
228
229
230 /* Function: rppAddInputPort ===================================================
231  * Abstract:
232  *     Utility function to add an standard single width input port.
233  */
234 static bool rppAddInputPort(SimStruct* S, int_T port, DTypeId type)
235 {
236     ssSetInputPortWidth(S, port, 1);
237     ssSetInputPortDataType(S, port, type);
238     ssSetInputPortComplexSignal(S, port, COMPLEX_NO);
239     ssSetInputPortDirectFeedThrough(S, port, true);
240     ssSetInputPortRequiredContiguous(S, port, true);
241 }
242
243 /* Function: rppAddInputVectorPort ===================================================
244  * Abstract:
245  *     Utility function to add an standard vector width input port.
246  */
247 static bool rppAddInputVectorPort(SimStruct* S, int_T port, DTypeId type, int_T size)
248 {
249     ssSetInputPortWidth(S, port, size);
250     ssSetInputPortDataType(S, port, type);
251     ssSetInputPortComplexSignal(S, port, COMPLEX_NO);
252     ssSetInputPortDirectFeedThrough(S, port, true);
253     ssSetInputPortRequiredContiguous(S, port, true);
254 }
255
256
257 /* Function: rppAddOutputPort ==================================================
258  * Abstract:
259  *     Utility function to add an standard single width output port.
260  */
261 static bool rppAddOutputPort(SimStruct* S, int_T port, DTypeId type)
262 {
263     ssSetOutputPortWidth(S, port, 1);
264     ssSetOutputPortDataType(S, port, type);
265     ssSetOutputPortComplexSignal(S, port, COMPLEX_NO);
266 }
267
268 /* Function: rppAddOutputVectorPort ==================================================
269  * Abstract:
270  *     Utility function to add an standard vector width output port.
271  */
272 static bool rppAddOutputVectorPort(SimStruct* S, int_T port, DTypeId type, int_T size)
273 {
274     ssSetOutputPortWidth(S, port, size);
275     ssSetOutputPortDataType(S, port, type);
276     ssSetOutputPortComplexSignal(S, port, COMPLEX_NO);
277 }
278
279
280 /* Function: rppSetStandardOptions =============================================
281  * Abstract:
282  *     Common / standard options for RPP blocks.
283  */
284 static void rppSetStandardOptions(SimStruct* S)
285 {
286     /* Specify the sim state compliance to be same as a built-in block */
287     ssSetSimStateCompliance(S, USE_DEFAULT_SIM_STATE);
288
289     /* Set the number of sample time. */
290     ssSetNumSampleTimes(S, 1);
291
292     /*
293      * All options have the form SS_OPTION_<name> and are documented in
294      * <matlabroot>/simulink/include/simstruc.h. The options should be
295      * combined with bitwise OR as in
296      *   ssSetOptions(S, (SS_OPTION_name1 | SS_OPTION_name2))
297      */
298     ssSetOptions(S,
299         SS_OPTION_WORKS_WITH_CODE_REUSE |
300         SS_OPTION_CAN_BE_CALLED_CONDITIONALLY |
301         /*SS_OPTION_EXCEPTION_FREE_CODE |*/
302         SS_OPTION_USE_TLC_WITH_ACCELERATOR);
303 }
304
305
306 /* Function: rppValidParamRange ================================================
307  * Abstract:
308  *     Validate that given parameter is scalar, numeric and between given range.
309  */
310 static bool rppValidParamRange(SimStruct* S, int_T parIdx, int_T mn, int_T mx)
311 {
312     const mxArray* raw = ssGetSFcnParam(S, parIdx);
313     if (mxGetNumberOfElements(raw) != 1) {
314         ssSetErrorStatus(S, "Parameter to S-function must be a scalar.");
315         return false;
316     }
317
318     if (!mxIsDouble(raw)) {
319         ssSetErrorStatus(S, "Parameter to S-function must be numeric.");
320         return false;
321     }
322
323     double num = (mxGetPr(raw))[0];
324     if (trunc(num) != num) {
325         /* printf("Num      : %2.6f\n", num); */
326         /* printf("Num trunc: %2.6f\n", trunc(num)); */
327         ssSetErrorStatus(S, "Parameter to S-function must be an integer.");
328         return false;
329     }
330
331     if ((num < mn) || (num > mx)) {
332         ssSetErrorStatus(S, "Parameter to S-function must be "
333                             "between specified range.");
334         return false;
335     }
336
337     return true;
338 }
339
340
341 /* Function: rppValidParamBoolean ==============================================
342  * Abstract:
343  *     Validate that given parameter is boolean (logical).
344  */
345 static bool rppValidParamBoolean(SimStruct* S, int_T parIdx)
346 {
347     const mxArray* raw = ssGetSFcnParam(S, parIdx);
348     if (!mxIsLogicalScalar(raw)) {
349         ssSetErrorStatus(S, "Parameter to S-function must be a scalar.");
350         return false;
351     }
352
353     return true;
354 }
355
356
357 /*
358  *==============================================================================
359  *=           BEGIN EXAMPLE CODE AND FUNCTIONS DOCUMENTATION                   =
360  *==============================================================================
361  */
362 #ifdef NEVER_DEFINED
363
364
365 /* Function: mdlCheckParameters ================================================
366  * Abstract:
367  *     mdlCheckParameters verifies new parameter settings whenever parameter
368  *     change or are re-evaluated during a simulation. When a simulation is
369  *     running, changes to S-function parameters can occur at any time during
370  *     the simulation loop.
371  *
372  *     See http://www.mathworks.com/help/simulink/sfg/mdlcheckparameters.html
373  */
374 #ifdef MATLAB_MEX_FILE
375 #define MDL_CHECK_PARAMETERS
376 static void mdlCheckParameters(SimStruct* S)
377 {
378     /* Check the parameter 1 */
379     if (!rppValidParamRange(S, 0, 1, 20)) {
380         return;
381     }
382 }
383 #endif
384
385
386 /* Function: mdlRTW ============================================================
387  * Abstract:
388  *     This function is called when the Real-Time Workshop is generating
389  *     the model.rtw file.
390  *
391  *     See http://www.mathworks.com/help/simulink/sfg/mdlrtw.html
392  */
393 #ifdef MATLAB_MEX_FILE
394 #define MDL_RTW
395 static void mdlRTW(SimStruct* S)
396 {
397     UNUSED_PARAMETER(S);
398 }
399 #endif
400
401
402 /* Function: mdlSetWorkWidths ==================================================
403  * Abstract:
404  *     The optional method, mdlSetWorkWidths is called after input port
405  *     width, output port width, and sample times of the S-function have
406  *     been determined to set any state and work vector sizes which are
407  *     a function of the input, output, and/or sample times.
408  *
409  *     Run-time parameters are registered in this method using methods
410  *     ssSetNumRunTimeParams, ssSetRunTimeParamInfo, and related methods.
411  *
412  *     See http://www.mathworks.com/help/simulink/sfg/mdlsetworkwidths.html
413  */
414 #ifdef MATLAB_MEX_FILE
415 #define MDL_SET_WORK_WIDTHS
416 static void mdlSetWorkWidths(SimStruct* S)
417 {
418     /* Set number of run-time parameters */
419     if (!ssSetNumRunTimeParams(S, 1)) {
420         return;
421     }
422
423     /* Register the run-time parameter 1 */
424     ssRegDlgParamAsRunTimeParam(S, 0, 0, "p1", SS_UINT8);
425 }
426 #endif
427
428
429 /* Function: mdlStart ==========================================================
430  * Abstract:
431  *     This function is called once at start of model execution. If you
432  *     have states that should be initialized once, this is the place
433  *     to do it.
434  *
435  *     See http://www.mathworks.com/help/simulink/sfg/mdlstart.html
436  */
437 #define MDL_START
438 static void mdlStart(SimStruct* S)
439 {
440     UNUSED_PARAMETER(S);
441 }
442
443 #endif /* NEVER_DEFINED */