--- /dev/null
+SF=$(wildcard sfunction_*.c)
+
+HTML = $(SF:%.c=%.html)
+MEX = $(SF:%.c=%.mexa64)
+
+all: $(MEX) $(HTML)
+
+%.mexa64: %.c
+ mex $(CFLAGS) $^
+
+MATLAB=$(shell cd $(dir $(shell readlink -f $$(which mex)))/..; pwd)
+CAN_BLOCKS=sfunction_cantransmit.mexa64 sfunction_canreceive.mexa64
+$(CAN_BLOCKS): CFLAGS=-I$(MATLAB)/toolbox/shared/can/src/scanutil -I$(MATLAB)/toolbox/rtw/targets/common/can/datatypes
+$(CAN_BLOCKS): $(MATLAB)/toolbox/rtw/targets/common/can/datatypes/sfun_can_util.c $(MATLAB)/toolbox/rtw/targets/common/can/datatypes/can_msg.c
+
+%.html: %.c
+ scripts/doc_parse.py --html $< > $@
--- /dev/null
+/* Copyright (C) 2013 Czech Technical University in Prague
+ *
+ * Authors:
+ * - Carlos Jenkins <carlos@jenkins.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are
+ * met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ *
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the
+ * distribution.
+ *
+ * 3. Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived
+ * from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+ * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+ * HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+ * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+ * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+ * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ * File : header.c
+ * Abstract:
+ * Common header for all RPP S-Functions.
+ * This file should be included at the beginning of a C-MEX S-Function block
+ * implementation after defining S_FUNCTION_NAME. It include refactored and
+ * commonly repeated structures that pollute S-Functions implementations
+ * (in conjunction with trailer.c). This file include basic includes,
+ * required definitions, macro definitions and documentation and commented
+ * prototypes for optional model calls/hooks.
+ *
+ * References:
+ * mdlInitializeSizes() : sfunctions.pdf p. 441 [Required]
+ * mdlInitializeSampleTimes() : sfunctions.pdf p. 436 [Required]
+ * mdlOutputs() : sfunctions.pdf p. 447 [Required]
+ * mdlTerminate() : sfunctions.pdf p. 493 [Required]
+ *
+ * .: S-Function callback methods :.
+ *
+ * ***********************
+ * * Start of simulation *
+ * ***********************
+ * |
+ * _ \_/
+ * | +--------------------+
+ * | | mdlInitializeSizes |
+ * | +--------------------+
+ * Initialization -| |
+ * | \_/
+ * | +--------------------------+
+ * | | mdlInitializeSampleTimes |
+ * |_ +--------------------------+
+ * |
+ * _______________\ |
+ * | /\_/
+ * | +------------+
+ * Simulation loop -| | mdlOutputs |
+ * | +------------+
+ * |_________________|
+ * |
+ * \_/
+ * +--------------+
+ * | mdlTerminate |
+ * +--------------+
+ *
+ * mdlCheckParameters() : sfunctions.pdf p. 421 [Optional]
+ * mdlRTW() : sfunctions.pdf p. 458 [Optional]
+ * mdlSetWorkWidths() : sfunctions.pdf p. 489 [Optional]
+ * mdlStart() : sfunctions.pdf p. 492 [Optional]
+ *
+ * trailer.c
+ */
+
+
+#ifndef S_FUNCTION_NAME
+#error 'Please include this file inside an S-Function implementation.'
+#endif
+
+#define S_FUNCTION_LEVEL 2
+
+
+/*
+ * Include C numerics library in order to use trunc() and other nice goodies.
+ */
+#include <math.h>
+
+/*
+ * Need to include simstruc.h for the definition of the SimStruct and
+ * its associated macro definitions.
+ */
+#include "simstruc.h"
+#define EDIT_OK(S, P_IDX) \
+ (!((ssGetSimMode(S)==SS_SIMMODE_SIZES_CALL_ONLY) && mxIsEmpty(ssGetSFcnParam(S, P_IDX))))
+#define SAMPLE_TIME (ssGetSFcnParam(S, 1))
+
+
+/* Function: isRealMatrix ======================================================
+ * Abstract:
+ * Utility function to verify that the mxArray is a real (double) finite
+ * matrix.
+ */
+static bool isRealMatrix(const mxArray * const m)
+{
+ if (mxIsNumeric(m) && mxIsDouble(m) && !mxIsLogical(m) && !mxIsComplex(m) &&
+ !mxIsSparse(m) && !mxIsEmpty(m) && mxGetNumberOfDimensions(m) == 2) {
+
+ const double * const data = mxGetPr(m);
+ const size_t numEl = mxGetNumberOfElements(m);
+ size_t i;
+
+ for (i = 0; i < numEl; i++) {
+ if (!mxIsFinite(data[i])) {
+ return(false);
+ }
+ }
+
+ return(true);
+
+ } else {
+
+ return(false);
+
+ }
+}
+
+
+/* Function: checkSampleTime ===================================================
+ * Abstract:
+ * Utility function to verify that sample time (for variable sample time
+ * blocks) is valid.
+ */
+static bool checkSampleTime(SimStruct* S, int paramNum)
+{
+ if EDIT_OK(S, paramNum) {
+
+ const real_T* sampleTime = NULL;
+ const size_t stArraySize = mxGetM(SAMPLE_TIME) * mxGetN(SAMPLE_TIME);
+
+ /* Sample time must be a real scalar value or 2 element array. */
+ if (isRealMatrix(SAMPLE_TIME) &&
+ (stArraySize == 1 || stArraySize == 2)) {
+
+ sampleTime = (real_T*) mxGetPr(SAMPLE_TIME);
+
+ } else {
+ ssSetErrorStatus(S,
+ "Invalid sample time. Sample time must be a "
+ "real scalar value or an array of two real values.");
+ return false;
+ }
+
+ if (sampleTime[0] < 0.0 && sampleTime[0] != -1.0) {
+ ssSetErrorStatus(S,
+ "Invalid sample time. Period must be non-negative or "
+ "-1 (for inherited).");
+ return false;
+ }
+
+ if (stArraySize == 2 && sampleTime[0] > 0.0 &&
+ sampleTime[1] >= sampleTime[0]) {
+ ssSetErrorStatus(S,
+ "Invalid sample time. Offset must be smaller than period.");
+ return false;
+ }
+
+ if (stArraySize == 2 && sampleTime[0] == -1.0 && sampleTime[1] != 0.0) {
+ ssSetErrorStatus(S,
+ "Invalid sample time. When period is -1, offset must be 0.");
+ return false;
+ }
+
+ if (stArraySize == 2 && sampleTime[0] == 0.0 &&
+ !(sampleTime[1] == 1.0)) {
+ ssSetErrorStatus(S,
+ "Invalid sample time. When period is 0, offset must be 1.");
+ return false;
+ }
+ }
+ return true;
+}
+
+
+/* Function: rppSetNumParams ===================================================
+ * Abstract:
+ * Utility function to set the number of expected parameters, verify that
+ * the number of expected parameters is equal to the number of parameters
+ * entered in the dialog box return, and that the values entered are correct
+ * (by calling S-Function specific mdlCheckParameters() function).
+ */
+static void mdlCheckParameters(SimStruct* S);
+static bool rppSetNumParams(SimStruct* S, int_T numParams)
+{
+ ssSetNumSFcnParams(S, numParams);
+
+ #ifdef MATLAB_MEX_FILE
+ if (ssGetNumSFcnParams(S) == ssGetSFcnParamsCount(S)) {
+
+ mdlCheckParameters(S);
+ if (ssGetErrorStatus(S) != NULL) {
+ return false;
+ }
+ } else {
+ /* Return if number of expected != number of actual parameters */
+ return false;
+ }
+ #endif
+
+ /* Set the parameters tunable status */
+ int i;
+ for (i = 0; i < numParams; i++) {
+ ssSetSFcnParamTunable(S, i, false);
+ }
+
+ return true;
+}
+
+
+/* Function: rppAddInputPort ===================================================
+ * Abstract:
+ * Utility function to add an standard single width input port.
+ */
+static bool rppAddInputPort(SimStruct* S, int_T port, DTypeId type)
+{
+ ssSetInputPortWidth(S, port, 1);
+ ssSetInputPortDataType(S, port, type);
+ ssSetInputPortComplexSignal(S, port, COMPLEX_NO);
+ ssSetInputPortDirectFeedThrough(S, port, true);
+ ssSetInputPortRequiredContiguous(S, port, true);
+}
+
+/* Function: rppAddInputVectorPort ===================================================
+ * Abstract:
+ * Utility function to add an standard vector width input port.
+ */
+static bool rppAddInputVectorPort(SimStruct* S, int_T port, DTypeId type, int_T size)
+{
+ ssSetInputPortWidth(S, port, size);
+ ssSetInputPortDataType(S, port, type);
+ ssSetInputPortComplexSignal(S, port, COMPLEX_NO);
+ ssSetInputPortDirectFeedThrough(S, port, true);
+ ssSetInputPortRequiredContiguous(S, port, true);
+}
+
+
+/* Function: rppAddOutputPort ==================================================
+ * Abstract:
+ * Utility function to add an standard single width output port.
+ */
+static bool rppAddOutputPort(SimStruct* S, int_T port, DTypeId type)
+{
+ ssSetOutputPortWidth(S, port, 1);
+ ssSetOutputPortDataType(S, port, type);
+ ssSetOutputPortComplexSignal(S, port, COMPLEX_NO);
+}
+
+/* Function: rppAddOutputVectorPort ==================================================
+ * Abstract:
+ * Utility function to add an standard vector width output port.
+ */
+static bool rppAddOutputVectorPort(SimStruct* S, int_T port, DTypeId type, int_T size)
+{
+ ssSetOutputPortWidth(S, port, size);
+ ssSetOutputPortDataType(S, port, type);
+ ssSetOutputPortComplexSignal(S, port, COMPLEX_NO);
+}
+
+
+/* Function: rppSetStandardOptions =============================================
+ * Abstract:
+ * Common / standard options for RPP blocks.
+ */
+static void rppSetStandardOptions(SimStruct* S)
+{
+ /* Specify the sim state compliance to be same as a built-in block */
+ ssSetSimStateCompliance(S, USE_DEFAULT_SIM_STATE);
+
+ /* Set the number of sample time. */
+ ssSetNumSampleTimes(S, 1);
+
+ /*
+ * All options have the form SS_OPTION_<name> and are documented in
+ * <matlabroot>/simulink/include/simstruc.h. The options should be
+ * combined with bitwise OR as in
+ * ssSetOptions(S, (SS_OPTION_name1 | SS_OPTION_name2))
+ */
+ ssSetOptions(S,
+ SS_OPTION_WORKS_WITH_CODE_REUSE |
+ SS_OPTION_CAN_BE_CALLED_CONDITIONALLY |
+ /*SS_OPTION_EXCEPTION_FREE_CODE |*/
+ SS_OPTION_USE_TLC_WITH_ACCELERATOR);
+}
+
+
+/* Function: rppValidParamRange ================================================
+ * Abstract:
+ * Validate that given parameter is scalar, numeric and between given range.
+ */
+static bool rppValidParamRange(SimStruct* S, int_T parIdx, int_T mn, int_T mx)
+{
+ const mxArray* raw = ssGetSFcnParam(S, parIdx);
+ if (mxGetNumberOfElements(raw) != 1) {
+ ssSetErrorStatus(S, "Parameter to S-function must be a scalar.");
+ return false;
+ }
+
+ if (!mxIsDouble(raw)) {
+ ssSetErrorStatus(S, "Parameter to S-function must be numeric.");
+ return false;
+ }
+
+ double num = (mxGetPr(raw))[0];
+ if (trunc(num) != num) {
+ /* printf("Num : %2.6f\n", num); */
+ /* printf("Num trunc: %2.6f\n", trunc(num)); */
+ ssSetErrorStatus(S, "Parameter to S-function must be an integer.");
+ return false;
+ }
+
+ if ((num < mn) || (num > mx)) {
+ ssSetErrorStatus(S, "Parameter to S-function must be "
+ "between specified range.");
+ return false;
+ }
+
+ return true;
+}
+
+
+/* Function: rppValidParamBoolean ==============================================
+ * Abstract:
+ * Validate that given parameter is boolean (logical).
+ */
+static bool rppValidParamBoolean(SimStruct* S, int_T parIdx)
+{
+ const mxArray* raw = ssGetSFcnParam(S, parIdx);
+ if (!mxIsLogicalScalar(raw)) {
+ ssSetErrorStatus(S, "Parameter to S-function must be a scalar.");
+ return false;
+ }
+
+ return true;
+}
+
+
+/*
+ *==============================================================================
+ *= BEGIN EXAMPLE CODE AND FUNCTIONS DOCUMENTATION =
+ *==============================================================================
+ */
+#ifdef NEVER_DEFINED
+
+
+/* Function: mdlCheckParameters ================================================
+ * Abstract:
+ * mdlCheckParameters verifies new parameter settings whenever parameter
+ * change or are re-evaluated during a simulation. When a simulation is
+ * running, changes to S-function parameters can occur at any time during
+ * the simulation loop.
+ *
+ * See http://www.mathworks.com/help/simulink/sfg/mdlcheckparameters.html
+ */
+#ifdef MATLAB_MEX_FILE
+#define MDL_CHECK_PARAMETERS
+static void mdlCheckParameters(SimStruct* S)
+{
+ /* Check the parameter 1 */
+ if (!rppValidParamRange(S, 0, 1, 20)) {
+ return;
+ }
+}
+#endif
+
+
+/* Function: mdlRTW ============================================================
+ * Abstract:
+ * This function is called when the Real-Time Workshop is generating
+ * the model.rtw file.
+ *
+ * See http://www.mathworks.com/help/simulink/sfg/mdlrtw.html
+ */
+#ifdef MATLAB_MEX_FILE
+#define MDL_RTW
+static void mdlRTW(SimStruct* S)
+{
+ UNUSED_PARAMETER(S);
+}
+#endif
+
+
+/* Function: mdlSetWorkWidths ==================================================
+ * Abstract:
+ * The optional method, mdlSetWorkWidths is called after input port
+ * width, output port width, and sample times of the S-function have
+ * been determined to set any state and work vector sizes which are
+ * a function of the input, output, and/or sample times.
+ *
+ * Run-time parameters are registered in this method using methods
+ * ssSetNumRunTimeParams, ssSetRunTimeParamInfo, and related methods.
+ *
+ * See http://www.mathworks.com/help/simulink/sfg/mdlsetworkwidths.html
+ */
+#ifdef MATLAB_MEX_FILE
+#define MDL_SET_WORK_WIDTHS
+static void mdlSetWorkWidths(SimStruct* S)
+{
+ /* Set number of run-time parameters */
+ if (!ssSetNumRunTimeParams(S, 1)) {
+ return;
+ }
+
+ /* Register the run-time parameter 1 */
+ ssRegDlgParamAsRunTimeParam(S, 0, 0, "p1", SS_UINT8);
+}
+#endif
+
+
+/* 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.
+ *
+ * See http://www.mathworks.com/help/simulink/sfg/mdlstart.html
+ */
+#define MDL_START
+static void mdlStart(SimStruct* S)
+{
+ UNUSED_PARAMETER(S);
+}
+
+#endif /* NEVER_DEFINED */
--- /dev/null
+
+import re
+import types
+
+core_types = [ ]
+
+class Error(Exception):
+ pass
+
+class ValidationError(Exception):
+ def __init__(self, value, msg = ""):
+ self.value = value
+ def __str__(self):
+ if type(self.value) == str:
+ return self.value
+ else:
+ return "Invalid value '%s'" % self.value
+
+class Util(object):
+ @staticmethod
+ def make_range_check(opt):
+ range = { }
+ for entry in list(opt.keys()):
+ if entry not in ('min', 'max', 'min-ex', 'max-ex'):
+ raise ValueError("illegal argument to make_range_check")
+
+ range[entry] = opt[entry]
+
+ def check_range(value):
+ if range.get('min' ) != None and value < range['min' ]: raise ValidationError(value)
+ if range.get('min-ex') != None and value <= range['min-ex']: raise ValidationError(value)
+ if range.get('max-ex') != None and value >= range['max-ex']: raise ValidationError(value)
+ if range.get('max' ) != None and value > range['max' ]: raise ValidationError(value)
+ return True
+
+ return check_range
+
+class Factory(object):
+ def __init__(self, opt={}):
+ self.prefix_registry = {
+ '': 'tag:codesimply.com,2008:rx/core/',
+ '.meta': 'tag:codesimply.com,2008:rx/meta/',
+ }
+
+ self.type_registry = {}
+ if opt.get("register_core_types", False):
+ for t in core_types: self.register_type(t)
+
+ @staticmethod
+ def _default_prefixes(): pass
+
+ def expand_uri(self, type_name):
+ if re.match('^\w+:', type_name): return type_name
+
+ m = re.match('^/([-._a-z0-9]*)/([-._a-z0-9]+)$', type_name)
+
+ if not m:
+ raise ValueError("couldn't understand type name '%s'" % type_name)
+
+ if not self.prefix_registry.get(m.group(1)):
+ raise ValueError(
+ "unknown prefix '%s' in type name '%s'" % (m.group(1), type_name)
+ )
+
+ return '%s%s' % (self.prefix_registry[ m.group(1) ], m.group(2))
+
+ def add_prefix(self, name, base):
+ if self.prefix_registry.get(name, None):
+ raise Error("the prefix '%s' is already registered" % name)
+
+ self.prefix_registry[name] = base;
+
+ def register_type(self, t):
+ t_uri = t.uri()
+
+ if self.type_registry.get(t_uri, None):
+ raise ValueError("type already registered for %s" % t_uri)
+
+ self.type_registry[t_uri] = t
+
+ def learn_type(self, uri, schema):
+ if self.type_registry.get(uri, None):
+ raise Error("tried to learn type for already-registered uri %s" % uri)
+
+ # make sure schema is valid
+ # should this be in a try/except?
+ self.make_schema(schema)
+
+ self.type_registry[uri] = { "schema": schema }
+
+ def make_schema(self, schema):
+ if type(schema) == str:
+ schema = { "type": schema }
+
+ if not type(schema) is dict:
+ raise Error('invalid schema argument to make_schema')
+
+ uri = self.expand_uri(schema["type"])
+
+ if not self.type_registry.get(uri): raise Error("unknown type %s" % uri)
+
+ type_class = self.type_registry[ uri ]
+
+ if type(type_class) is dict:
+ if not set(schema.keys()).issubset(set(['type'])):
+ raise Error('composed type does not take check arguments');
+ return self.make_schema(type_class["schema"])
+ else:
+ return type_class(schema, self)
+
+class _CoreType(object):
+ @classmethod
+ def uri(self):
+ return 'tag:codesimply.com,2008:rx/core/' + self.subname()
+
+ def __init__(self, schema, rx):
+ if not set(schema.keys()).issubset(set(['type'])):
+ raise Error('unknown parameter for //%s' % self.subname())
+
+ def check(self, value): raise ValidationError(value)
+
+class AllType(_CoreType):
+ @staticmethod
+ def subname(): return 'all'
+
+ def __init__(self, schema, rx):
+ if not set(schema.keys()).issubset(set(('type', 'of'))):
+ raise Error('unknown parameter for //all')
+
+ if not(schema.get('of') and len(schema.get('of'))):
+ raise Error('no alternatives given in //all of')
+
+ self.alts = [ rx.make_schema(s) for s in schema['of'] ]
+
+ def check(self, value):
+ for schema in self.alts:
+ if (not schema.check(value)): raise ValidationError(value)
+ return True
+
+class AnyType(_CoreType):
+ @staticmethod
+ def subname(): return 'any'
+
+ def __init__(self, schema, rx):
+ self.alts = None
+
+ if not set(schema.keys()).issubset(set(('type', 'of'))):
+ raise Error('unknown parameter for //any')
+
+ if schema.get('of') != None:
+ if not schema['of']: raise Error('no alternatives given in //any of')
+ self.alts = [ rx.make_schema(alt) for alt in schema['of'] ]
+
+ def check(self, value):
+ if self.alts is None: return True
+
+ for alt in self.alts:
+ try:
+ if alt.check(value): return True
+ except ValidationError:
+ pass
+
+ raise ValidationError(value)
+
+class ArrType(_CoreType):
+ @staticmethod
+ def subname(): return 'arr'
+
+ def __init__(self, schema, rx):
+ self.length = None
+
+ if not set(schema.keys()).issubset(set(('type', 'contents', 'length'))):
+ raise Error('unknown parameter for //arr')
+
+ if not schema.get('contents'):
+ raise Error('no contents provided for //arr')
+
+ self.content_schema = rx.make_schema(schema['contents'])
+
+ if schema.get('length'):
+ self.length = Util.make_range_check( schema["length"] )
+
+ def check(self, value):
+ if not(type(value) in [ type([]), type(()) ]): raise ValidationError(value)
+ if self.length and not self.length(len(value)): raise ValidationError(value)
+
+ for item in value:
+ if not self.content_schema.check(item): raise ValidationError(value)
+
+ return True;
+
+class BoolType(_CoreType):
+ @staticmethod
+ def subname(): return 'bool'
+
+ def check(self, value):
+ if value is True or value is False: return True
+ raise ValidationError(value)
+
+class DefType(_CoreType):
+ @staticmethod
+ def subname(): return 'def'
+
+ def check(self, value): return not(value is None)
+
+class FailType(_CoreType):
+ @staticmethod
+ def subname(): return 'fail'
+
+ def check(self, value): raise ValidationError(value)
+
+class IntType(_CoreType):
+ @staticmethod
+ def subname(): return 'int'
+
+ def __init__(self, schema, rx):
+ if not set(schema.keys()).issubset(set(('type', 'range', 'value'))):
+ raise Error('unknown parameter for //int')
+
+ self.value = None
+ if 'value' in schema:
+ if not type(schema['value']) in (float, int):
+ raise Error('invalid value parameter for //int')
+ if schema['value'] % 1 != 0:
+ raise Error('invalid value parameter for //int')
+ self.value = schema['value']
+
+ self.range = None
+ if 'range' in schema:
+ self.range = Util.make_range_check( schema["range"] )
+
+ def check(self, value):
+ if not(type(value) in (float, int)): raise ValidationError(value)
+ if value % 1 != 0: raise ValidationError(value)
+ if self.range and not self.range(value): raise ValidationError(value)
+ if (not self.value is None) and value != self.value: raise ValidationError(value)
+ return True
+
+class MapType(_CoreType):
+ @staticmethod
+ def subname(): return 'map'
+
+ def __init__(self, schema, rx):
+ self.allowed = set()
+
+ if not set(schema.keys()).issubset(set(('type', 'values'))):
+ raise Error('unknown parameter for //map')
+
+ if not schema.get('values'):
+ raise Error('no values given for //map')
+
+ self.value_schema = rx.make_schema(schema['values'])
+
+ def check(self, value):
+ if not(type(value) is type({})): raise ValidationError(value)
+
+ for v in list(value.values()):
+ if not self.value_schema.check(v): raise ValidationError(value)
+
+ return True;
+
+class NilType(_CoreType):
+ @staticmethod
+ def subname(): return 'nil'
+
+ def check(self, value): return value is None
+
+class NumType(_CoreType):
+ @staticmethod
+ def subname(): return 'num'
+
+ def __init__(self, schema, rx):
+ if not set(schema.keys()).issubset(set(('type', 'range', 'value'))):
+ raise Error('unknown parameter for //num')
+
+ self.value = None
+ if 'value' in schema:
+ if not type(schema['value']) in (float, int):
+ raise Error('invalid value parameter for //num')
+ self.value = schema['value']
+
+ self.range = None
+
+ if schema.get('range'):
+ self.range = Util.make_range_check( schema["range"] )
+
+ def check(self, value):
+ if not(type(value) in (float, int)): raise ValidationError(value)
+ if self.range and not self.range(value): raise ValidationError(value)
+ if (not self.value is None) and value != self.value: raise ValidationError(value)
+ return True
+
+class OneType(_CoreType):
+ @staticmethod
+ def subname(): return 'one'
+
+ def check(self, value):
+ if type(value) in (int, float, int, bool, str): return True
+
+ raise ValidationError(value)
+
+class RecType(_CoreType):
+ @staticmethod
+ def subname(): return 'rec'
+
+ def __init__(self, schema, rx):
+ if not set(schema.keys()).issubset(set(('type', 'rest', 'required', 'optional'))):
+ raise Error('unknown parameter for //rec')
+
+ self.known = set()
+ self.rest_schema = None
+ if schema.get('rest'): self.rest_schema = rx.make_schema(schema['rest'])
+
+ for which in ('required', 'optional'):
+ self.__setattr__(which, { })
+ for field in list(schema.get(which, {}).keys()):
+ if field in self.known:
+ raise Error('%s appears in both required and optional' % field)
+
+ self.known.add(field)
+
+ self.__getattribute__(which)[field] = rx.make_schema(
+ schema[which][field]
+ )
+
+ def check(self, value):
+ if not(type(value) is type({})): raise ValidationError(value)
+
+ unknown = [ ]
+ for field in list(value.keys()):
+ if not field in self.known: unknown.append(field)
+
+ if len(unknown) and not self.rest_schema: raise ValidationError("Unknown fields %s" % unknown)
+
+ for field in list(self.required.keys()):
+ if field not in value: raise ValidationError("Missing required field '%s'" % field)
+ if not self.required[field].check( value[field] ): raise ValidationError(value)
+
+ for field in list(self.optional.keys()):
+ if field not in value: continue
+ if not self.optional[field].check( value[field] ): raise ValidationError(value)
+
+ if len(unknown):
+ rest = { }
+ for field in unknown: rest[field] = value[field]
+ if not self.rest_schema.check(rest): raise ValidationError(value)
+
+ return True;
+
+class SeqType(_CoreType):
+ @staticmethod
+ def subname(): return 'seq'
+
+ def __init__(self, schema, rx):
+ if not set(schema.keys()).issubset(set(('type', 'contents', 'tail'))):
+ raise Error('unknown parameter for //seq')
+
+ if not schema.get('contents'):
+ raise Error('no contents provided for //seq')
+
+ self.content_schema = [ rx.make_schema(s) for s in schema["contents"] ]
+
+ self.tail_schema = None
+ if (schema.get('tail')):
+ self.tail_schema = rx.make_schema(schema['tail'])
+
+ def check(self, value):
+ if not(type(value) in [ type([]), type(()) ]): raise ValidationError(value)
+
+ if len(value) < len(self.content_schema):
+ raise ValidationError(value)
+
+ for i in range(0, len(self.content_schema)):
+ if not self.content_schema[i].check(value[i]):
+ raise ValidationError(value)
+
+ if len(value) > len(self.content_schema):
+ if not self.tail_schema: raise ValidationError(value)
+
+ if not self.tail_schema.check(value[ len(self.content_schema) : ]):
+ raise ValidationError(value)
+
+ return True;
+
+class StrType(_CoreType):
+ @staticmethod
+ def subname(): return 'str'
+
+ def __init__(self, schema, rx):
+ if not set(schema.keys()).issubset(set(('type', 'value', 'length'))):
+ raise Error('unknown parameter for //str')
+
+ self.value = None
+ if 'value' in schema:
+ if not type(schema['value']) == str:
+ raise Error('invalid value parameter for //str')
+ self.value = schema['value']
+
+ self.length = None
+ if 'length' in schema:
+ self.length = Util.make_range_check( schema["length"] )
+
+ def check(self, value):
+ if not type(value) == str: raise ValidationError(value)
+ if (not self.value is None) and value != self.value: raise ValidationError(value)
+ if self.length and not self.length(len(value)): raise ValidationError(value)
+ return True
+
+core_types = [
+ AllType, AnyType, ArrType, BoolType, DefType,
+ FailType, IntType, MapType, NilType, NumType,
+ OneType, RecType, SeqType, StrType
+]
--- /dev/null
+#!/usr/bin/env python3
+
+import yaml
+import argparse
+import Rx
+import sys
+import subprocess
+import os
+from string import Template
+
+parser = argparse.ArgumentParser()
+parser.add_argument("file", help="file to process", nargs='+')
+parser.add_argument("--html", help="output block description as HTML",
+ action = 'store_true')
+parser.add_argument("--latex", help="output block description as LaTeX",
+ action = 'store_true')
+parser.add_argument("--latex-table", help="output block status table as LaTeX",
+ action = 'store_true')
+args = parser.parse_args()
+
+mydir = os.path.dirname(os.path.realpath(__file__))
+
+def print_markdown_as(format, text):
+ sys.stdout.flush()
+ proc = subprocess.Popen(['pandoc', '-f', 'markdown', '-t', format], stdin = subprocess.PIPE)
+ proc.stdin.write(bytes(text, 'UTF-8'))
+ proc.communicate()
+ proc.stdin.close()
+ if proc.returncode:
+ raise Exception("pandoc failed: %d" % proc.returncode)
+
+def print_latex_desc(doc):
+ def iodef_str(iodef):
+ if iodef is None: return "None"
+ str='%d\n\\begin{enumerate}\n' % len(iodef)
+ for io in iodef:
+ str += Template('\\item {\\bf $name} $type').substitute(io)
+ if 'range' in io:
+ str += ' %s' % io['range']
+ str += '\n'
+ return str +'\end{enumerate}'
+
+ print("\\newpage\n")
+ print("\\subsubsection{%s}\n" % doc['Name'])
+ print("\\begin{description}\n")
+ print("\\item[Inputs:] %s\n" % iodef_str(doc['Inputs']))
+ print("\\item[Outputs:] %s\n" % iodef_str(doc['Outputs']))
+ print("\\item[Parameters:] %s\n" % iodef_str(doc['Parameters']))
+ print("\\end{description}\n")
+
+ print_markdown_as('latex', doc['Description'])
+
+ print("\n\\textbf{Status:}")
+ print("\\begin{multicols}{3}")
+ if doc['Status']['Tested']:
+ print("\\begin{compactitem}")
+ print("\\item \\textbf{Tested}:")
+ print(" \\begin{compactitem}")
+ print("\n".join(["\\item %s" % i.replace('_', '\\_') for i in doc['Status']['Tested']]))
+ print(" \\end{compactitem}")
+ print("\\end{compactitem}")
+ else:
+ print("\\ ")
+
+ print("\\vfill\\columnbreak")
+
+ if doc['Status']['Untested']:
+ print("\\begin{compactitem}")
+ print("\\item \\textbf{Untested}:")
+ print(" \\begin{compactitem}")
+ print("\n".join(["\\item %s" % i.replace('_', '\\_') for i in doc['Status']['Untested']]))
+ print(" \\end{compactitem}")
+ print("\\end{compactitem}")
+ else:
+ print("\\ ")
+
+ print("\\vfill\\columnbreak")
+
+ if doc['Status']['Not working']:
+ print("\\begin{compactitem}")
+ print("\\item \\textbf{Not working}:")
+ print(" \\begin{compactitem}")
+ print("\n".join(["\\item %s" % i.replace('_', '\\_') for i in doc['Status']['Not working']]))
+ print(" \\end{compactitem}")
+ print("\\end{compactitem}")
+ else:
+ print("\\ ")
+
+ print("\\end{multicols}\n")
+
+ if doc.get('RPP API functions used', None) is not None:
+ print("\\textbf{RPP API functions used:}")
+ print("\\begin{compactitem}")
+ print("\n".join(["\\item \\texttt{%s}" % i.replace('_', '\\_') for i in doc['RPP API functions used']]))
+ print("\\end{compactitem}")
+
+ if doc.get('Relevant demos', None) is not None:
+ print("\\textbf{Relevant demos:}")
+ print("\\begin{compactitem}")
+ print("\n".join(["\\item %s" % i.replace('_', '\\_') for i in doc['Relevant demos']]))
+ print("\\end{compactitem}")
+
+def process_file(f):
+ yaml_doc = None
+ for line in open(f, 'r'):
+ if yaml_doc:
+ yaml_doc += line
+ elif line.startswith("%YAML"):
+ yaml_doc = line
+ if line == '...\n':
+ break
+ if yaml_doc is None:
+ raise Exception("No line starting with '%%YAML' found in %s" % f)
+
+ doc = yaml.load(yaml_doc)
+ schema = yaml.load(open(mydir+'/schema.yaml', 'r'))
+
+ rx = Rx.Factory({ "register_core_types": True })
+ rpp_block_doc_schema = rx.make_schema(schema)
+ try:
+ rpp_block_doc_schema.check(doc)
+ except Rx.ValidationError as e:
+ raise Exception("Validation error in %s: %s" % (f, e))
+ #raise
+
+ if args.html:
+ print_markdown_as('html', doc['Description'])
+ if args.latex:
+ print_latex_desc(doc)
+ if args.latex_table:
+ global last_category
+ if last_category == doc['Category']: doc['Category']=''
+ doc['Header'] = doc['Header'].replace('_', '\\_')
+ if doc['Status']['Not working']: doc['ShortStatus'] = '$\\alpha$'
+ elif doc['Status']['Untested']: doc['ShortStatus'] = '$\\beta$'
+ elif not doc['Status']['Tested']: doc['ShortStatus'] = '$\\beta$'
+ else: doc['ShortStatus'] = 'Stable'
+ print(Template("$Category & $Name & $ShortStatus & $Mnemonic & \\texttt{$Header} \\\\").substitute(doc))
+ if doc['Category']:
+ last_category = doc['Category']
+
+last_category = None
+for f in args.file:
+ process_file(f)
--- /dev/null
+type: //rec
+required:
+ Name: //str
+ Mnemonic: //str
+ Header: //str
+ Category: //str
+ Inputs: &iodef
+ type: //any
+ of:
+ - //nil
+ - type: //arr
+ contents:
+ type: //rec
+ required:
+ name: //str
+ type: //str
+ optional:
+ range: //str
+ Outputs: *iodef
+ Parameters: *iodef
+ Description: //str
+ Status:
+ type: //rec
+ required:
+ Tested: &strarray
+ type: //any
+ of:
+ - //nil
+ - type: //arr
+ contents: //str
+ Untested: *strarray
+ Not working: *strarray
+optional:
+ RPP API functions used: *strarray
+ Relevant demos: *strarray
--- /dev/null
+/* Copyright (C) 2014 Czech Technical University in Prague
+ *
+ * Authors:
+ * - Michal Horn <hornmich@fel.cvut.cz>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are
+ * met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ *
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the
+ * distribution.
+ *
+ * 3. Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived
+ * from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+ * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+ * HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+ * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+ * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+ * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ * File : sfunction_canrecive.c
+ * Abstract:
+ * C-MEX S-function block for RPP CAN bus receive message.
+ *
+ * References:
+ * header.c
+ * trailer.c
+ *
+ * Compile with:
+ * mex(['-I' matlabroot '/toolbox/shared/can/src/scanutil'], ['-I' matlabroot '/toolbox/rtw/targets/common/can/datatypes'], 'sfunction_canreceive.c', [matlabroot '/toolbox/rtw/targets/common/can/datatypes/sfun_can_util.c'], [matlabroot '/toolbox/rtw/targets/common/can/datatypes/can_msg.c'])
+ */
+
+/*
+%YAML 1.2
+---
+Name: CAN Receive
+Category: CAN
+Header: rpp/can.h
+Mnemonic: CANR
+
+Inputs:
+
+Outputs:
+ - { name: "f()", type: "Function call" }
+ - { name: "Msg", type: "uint8, uint16, uint32 or CAN MESSAGE" }
+
+Parameters:
+ - { name: "Module", type: "Choice", range: "CAN1, CAN2, CAN3" }
+ - { name: "Message ID type", type: "Choice", range: "Standard, Extended, Mixed" }
+ - { name: "Message ID filter", type: "Choice", range: "Single ID, ID and mask" }
+ - { name: "Message ID", type: "uint32" }
+ - { name: "Message ID mask", type: "uint8" }
+ - { name: "Data type", type: "Choice", range: "uint8, uint16, uint32, CAN MESSAGE TYPE" }
+ - { name: "Automatic mailbox number", type: "bool" }
+ - { name: "Mailbox number (0-31)", type: "int8" }
+
+# Description is in Markdown mark-up
+Description: |
+
+ This block allows receiving messages from the CAN bus. It can be
+ configured for any of the CAN ports (modules) CAN1, CAN2 or CAN3.
+
+ The acceptance rules for message reception can be specified by a
+ *Message ID* parameter and optionally by a *Message ID mask*.
+ Specifying the mask allows to receive messages with multiple IDs.
+ The block supports both, the Standard (11b ID) and the Extended (29b
+ ID) frame formats. Note that if Mixed message ID type is selected,
+ the blocks will receive both frame types, but the Standard Message
+ ID and optionally the Message ID mask has to be shifted by 18 bits
+ to the left to correspond with the extended IDs and masks. For
+ example, if Message ID parameter is set to 0x80000 and mask
+ to 0x1ffbfff, the block will receive SFF messages with IDs 0x002 and
+ 0x003 and EFF IDs 0x00080000 and 0x000c0000.
+
+ The mailbox number can be assigned automatically or manually. Automatic mailbox
+ numbers are generated in ascending order from 0 to 31. Every mailbox must have a unique
+ number. It is possible to mix blocks with automatically and manually
+ assigned mailboxes. If the manually assigned mailbox number would
+ collide with the automatic one then the automatically generated
+ block will get assigned a next higher non-colliding ID.
+ The mailbox numbers are shared between CAN Transmit and CAN Receive
+ blocks with the same CAN port (module) parameter.
+
+ The output of this block is a message data in selected format: uint8, uint16, uint32
+ or CAN\_MESSAGE. The CAN\_MESSAGE object can be unpacked by `CAN Unpack` block.
+
+ Every time a message is received, the function call on `f()` output
+ signal is triggered and the received message data is appears on the
+ `Msg` output port. See `cantransmit.slx` demo for examples of
+ different configurations and the usage of the CAN blocks.
+
+ In order to use this block, there must be a `CAN Configure` block in the model.
+
+Status:
+ Tested:
+ - Reception of messages with a configured ID.
+ - Rejection of messages with other ID then the configured one. FIXME
+ - Reception of messages with a set of IDs specified by a ID and mask.
+ - Reception of messages with Standard ID type, rejection of the messages with Extended ID type and vice versa.
+ - Reception of messages with both messages ID types.
+ - Automatic generation of mailboxes numbers with combination with manual specification, duplicate mailbox numbers detection.
+ - Function call triggering when new message is accepted
+ Untested:
+ - Handling of error states on CAN bus
+ Not working:
+ - Receiving at baudrate higher than 700kb
+ - External mode - throwing syntax error during compilation
+
+RPP API functions used:
+ - rpp_can_read()
+
+Relevant demos:
+ - cantransmit
+ - can_demo
+...
+*/
+
+
+#define S_FUNCTION_NAME sfunction_canreceive
+
+#include "header.c"
+#include <stdio.h>
+#include "sfun_can_util.h"
+#include "simstruc.h"
+
+#define MSG_TYPE_STANDART_MAX 2048
+#define MSG_TYPE_EXTENDED_MAX 536870912
+#define MAILBOX_ID_MIN 1
+#define MAILBOX_MAX_CNT 64
+
+#define PARAM_NAME_MODULE_ID "module_id"
+#define PARAM_NAME_MAILBOX_ID "mailbox_id"
+#define PARAM_NAME_MSG_TYPE "message_type"
+#define PARAM_NAME_MSG_ID "message_id"
+#define PARAM_NAME_DATA_TYPE "data_type"
+#define PARAM_NAME_MSG_FILTER "message_filter"
+#define PARAM_NAME_MSG_MASK "message_mask"
+#define PARAM_NAME_MAILBOX_AUTO "mailbox_auto"
+
+/** Identifiers of the block parameters */
+enum params{
+ PARAM_MODULE_ID,
+ PARAM_MAILBOX_ID,
+ PARAM_MSG_TYPE,
+ PARAM_MSG_ID,
+ PARAM_DATA_TYPE,
+ PARAM_MSG_FILTER,
+ PARAM_MSG_MASK,
+ PARAM_MAILBOX_AUTO,
+ PARAM_COUNT
+};
+
+enum message_data_type {
+ DATA_TYPE_UINT8 = 1,
+ DATA_TYPE_UINT16 = 2,
+ DATA_TYPE_UINT32 = 3,
+ DATA_TYPE_CAN_MESSAGE = 4
+};
+
+enum message_id_type {
+ MSG_ID_STANDART,
+ MSG_ID_EXTENDED,
+ MSG_ID_MIXED
+};
+
+enum outputs {
+ OUT_FNC_CALL,
+ OUT_MSG,
+ OUT_COUNT
+};
+
+static bool msg_received;
+
+static void mdlInitializeSizes(SimStruct *S){
+
+ CAN_Common_MdlInitSizes(S);
+
+ /*DTypeId type;*/
+
+ if(!rppSetNumParams(S, PARAM_COUNT)) {
+ return;
+ }
+
+ /* No input ports */
+ if(!ssSetNumInputPorts(S, 0)) {
+ return;
+ }
+
+ /*
+ * Configure output ports: 1
+ * - Received Message
+ * - Message is received
+ */
+ if(!ssSetNumOutputPorts(S, OUT_COUNT)) {
+ return;
+ }
+ rppAddOutputPort(S, OUT_FNC_CALL, SS_FCN_CALL);
+
+ if ((int_T)mxGetPr(ssGetSFcnParam(S, PARAM_DATA_TYPE))[0] == DATA_TYPE_UINT8) {
+ rppAddOutputPort(S, OUT_MSG, SS_UINT8);
+ }
+ else if ((int_T)mxGetPr(ssGetSFcnParam(S, PARAM_DATA_TYPE))[0] == DATA_TYPE_UINT16) {
+ rppAddOutputPort(S, OUT_MSG, SS_UINT16);
+ }
+ else if ((int_T)mxGetPr(ssGetSFcnParam(S, PARAM_DATA_TYPE))[0] == DATA_TYPE_UINT32) {
+ rppAddOutputPort(S, OUT_MSG, SS_UINT32);
+ }
+ else {
+ rppAddOutputPort(S, OUT_MSG, ssGetDataTypeId(S, "CAN_MESSAGE"));
+ }
+
+ /* Set standard options for this block */
+ rppSetStandardOptions(S);
+}
+
+
+#ifdef MATLAB_MEX_FILE
+#define MDL_CHECK_PARAMETERS
+
+static void mdlCheckParameters(SimStruct *S){
+ /* Check the parameter mailbox number */
+ if ((int_T)mxGetPr(ssGetSFcnParam(S, PARAM_MAILBOX_AUTO))[0] == 0) {
+ if (!rppValidParamRange(S, PARAM_MAILBOX_ID, MAILBOX_ID_MIN, MAILBOX_ID_MIN + MAILBOX_MAX_CNT)) {
+ return;
+ }
+ }
+
+ int min = 0;
+ int max = 0;
+ if ((int_T)mxGetPr(ssGetSFcnParam(S, PARAM_MSG_TYPE))[0] == MSG_ID_STANDART) {
+ max = MSG_TYPE_STANDART_MAX;
+ }
+ else {
+ max = MSG_TYPE_EXTENDED_MAX;
+ }
+
+ /* Check the parameter message identifier */
+ if (!rppValidParamRange(S, PARAM_MSG_ID, min, max)) {
+ return;
+ }
+}
+#endif
+
+static void mdlInitializeSampleTimes(SimStruct *S)
+{
+ ssSetSampleTime(S, 0, INHERITED_SAMPLE_TIME);
+ ssSetOffsetTime(S, 0, 0);
+
+ ssSetCallSystemOutput(S,0); /* call on first element */
+}
+
+
+#ifdef MATLAB_MEX_FILE
+#define MDL_SET_WORK_WIDTHS
+static void mdlSetWorkWidths(SimStruct *S){
+
+ if(!ssSetNumRunTimeParams(S, PARAM_COUNT)) {
+ return;
+ }
+
+ ssRegDlgParamAsRunTimeParam(S, PARAM_MODULE_ID, PARAM_MODULE_ID, PARAM_NAME_MODULE_ID, SS_UINT8);
+ ssRegDlgParamAsRunTimeParam(S, PARAM_MAILBOX_ID, PARAM_MAILBOX_ID, PARAM_NAME_MAILBOX_ID, SS_INT8);
+ ssRegDlgParamAsRunTimeParam(S, PARAM_MSG_TYPE, PARAM_MSG_TYPE, PARAM_NAME_MSG_TYPE, SS_UINT16);
+ ssRegDlgParamAsRunTimeParam(S, PARAM_MSG_ID, PARAM_MSG_ID, PARAM_NAME_MSG_ID, SS_UINT32);
+ ssRegDlgParamAsRunTimeParam(S, PARAM_DATA_TYPE, PARAM_DATA_TYPE, PARAM_NAME_DATA_TYPE, SS_UINT8);
+ ssRegDlgParamAsRunTimeParam(S, PARAM_MSG_FILTER, PARAM_MSG_FILTER, PARAM_NAME_MSG_FILTER, SS_UINT8);
+ ssRegDlgParamAsRunTimeParam(S, PARAM_MSG_MASK, PARAM_MSG_MASK, PARAM_NAME_MSG_MASK, SS_UINT32);
+ ssRegDlgParamAsRunTimeParam(S, PARAM_MAILBOX_AUTO, PARAM_MAILBOX_AUTO, PARAM_NAME_MAILBOX_AUTO, SS_BOOLEAN);
+}
+#endif
+
+#define UNUSED_MDLOUTPUTS
+#define UNUSED_MDLTERMINATE
+#include "trailer.c"
--- /dev/null
+/* Copyright (C) 2014 Czech Technical University in Prague
+ *
+ * Authors:
+ * - Michal Horn <hornmich@fel.cvut.cz>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are
+ * met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ *
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the
+ * distribution.
+ *
+ * 3. Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived
+ * from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+ * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+ * HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+ * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+ * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+ * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ * File : sfunction_cansetup.c
+ * Abstract:
+ * C-MEX S-function block for RPP CAN bus setup.
+ *
+ * References:
+ * header.c
+ * trailer.c
+ *
+ * Compile with:
+ * <matlabroot>/bin/mex sfunction_cansetup.c
+ */
+
+/*
+%YAML 1.2
+---
+Name: CAN Setup
+Category: CAN
+Header: rpp/can.h
+Mnemonic: CANC
+
+Inputs:
+
+Outputs:
+
+Parameters:
+ - { name: "Baud rate for CAN bus port 1 [bps]", type: "uint32", range: "1 – 10000000" }
+ - { name: "Baud rate for CAN bus port 2 [bps]", type: "uint32", range: "1 – 10000000" }
+ - { name: "Baud rate for CAN bus port 3 [bps]", type: "uint32", range: "1 – 10000000" }
+
+# Description is in Markdown mark-up
+Description: |
+
+ This block configures the CAN bus controllers. Exactly one CAN bus
+ configuration block must be in the model if any of the CAN Receive
+ or CAN Transmit block is used.
+
+Status:
+ Tested:
+ - Configuring CAN1, CAN2 and CAN3
+ Untested:
+ Not working:
+ - Receiving at baudrate higher than 700kb
+ - External mode - throwing syntax error during compilation
+
+RPP API functions used:
+ - rpp_can_init()
+
+Relevant demos:
+ - cantransmit
+ - can_demo
+...
+*/
+
+
+#define S_FUNCTION_NAME sfunction_cansetup
+#include "header.c"
+#include <stdio.h>
+
+#define BAUDRATE_MIN 1
+#define BAUDRATE_MAX 1000000
+
+#define BAUDRATE_CAN1_PARAM_NAME "baudrate_can1"
+#define BAUDRATE_CAN2_PARAM_NAME "baudrate_can2"
+#define BAUDRATE_CAN3_PARAM_NAME "baudrate_can3"
+
+/** Identifiers of the block parameters */
+enum params{
+ PARAM_CAN1_BAUDRATE,
+ PARAM_CAN2_BAUDRATE,
+ PARAM_CAN3_BAUDRATE,
+ PARAM_COUNT
+};
+
+static void mdlInitializeSizes(SimStruct *S)
+{
+ if (!rppSetNumParams(S, PARAM_COUNT)) {
+ return;
+ }
+
+ /* No input ports */
+ if (!ssSetNumInputPorts(S, 0)) {
+ return;
+ }
+
+ /* No output ports */
+ if (!ssSetNumOutputPorts(S, 0)) {
+ return;
+ }
+
+ rppSetStandardOptions(S);
+ void CAN_Common_MdlInitSizes(SimStruct *S);
+}
+
+
+#ifdef MATLAB_MEX_FILE
+#define MDL_CHECK_PARAMETERS
+static void mdlCheckParameters(SimStruct *S)
+{
+ /* Check the parameter CAN1 baudrate */
+ if (!rppValidParamRange(S, PARAM_CAN1_BAUDRATE, BAUDRATE_MIN, BAUDRATE_MAX)) {
+ return;
+ }
+ /* Check the parameter CAN2 baudrate */
+ if (!rppValidParamRange(S, PARAM_CAN2_BAUDRATE, BAUDRATE_MIN, BAUDRATE_MAX)) {
+ return;
+ }
+ /* Check the parameter CAN3 baudrate */
+ if (!rppValidParamRange(S, PARAM_CAN3_BAUDRATE, BAUDRATE_MIN, BAUDRATE_MAX)) {
+ return;
+ }
+}
+#endif
+
+
+#ifdef MATLAB_MEX_FILE
+#define MDL_SET_WORK_WIDTHS
+static void mdlSetWorkWidths(SimStruct *S)
+{
+
+ if (!ssSetNumRunTimeParams(S, PARAM_COUNT)) {
+ return;
+ }
+
+ ssRegDlgParamAsRunTimeParam(S, PARAM_CAN1_BAUDRATE, PARAM_CAN1_BAUDRATE, BAUDRATE_CAN1_PARAM_NAME, SS_UINT32);
+ ssRegDlgParamAsRunTimeParam(S, PARAM_CAN2_BAUDRATE, PARAM_CAN2_BAUDRATE, BAUDRATE_CAN2_PARAM_NAME, SS_UINT32);
+ ssRegDlgParamAsRunTimeParam(S, PARAM_CAN3_BAUDRATE, PARAM_CAN3_BAUDRATE, BAUDRATE_CAN3_PARAM_NAME, SS_UINT32);
+}
+#endif
+
+#define COMMON_MDLINITIALIZESAMPLETIMES_INHERIT
+#define UNUSED_MDLOUTPUTS
+#define UNUSED_MDLTERMINATE
+#include "trailer.c"
--- /dev/null
+/* Copyright (C) 2013-2014 Czech Technical University in Prague
+ *
+ * Authors:
+ * - Michal Horn <hornmich@fel.cvut.cz>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are
+ * met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ *
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the
+ * distribution.
+ *
+ * 3. Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived
+ * from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+ * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+ * HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+ * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+ * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+ * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ * File : sfunction_cantransmit.c
+ * Abstract:
+ * C-MEX S-function block for RPP CAN bus transmit message.
+ *
+ * References:
+ * header.c
+ * trailer.c
+ *
+ * Compile with:
+ * mex(['-I' matlabroot '/toolbox/shared/can/src/scanutil'], ['-I' matlabroot '/toolbox/rtw/targets/common/can/datatypes'], 'sfunction_cantransmit.c', [matlabroot '/toolbox/rtw/targets/common/can/datatypes/sfun_can_util.c'], [matlabroot '/toolbox/rtw/targets/common/can/datatypes/can_msg.c'])
+ */
+
+/*
+%YAML 1.2
+---
+Name: CAN Transmit
+Category: CAN
+Header: rpp/can.h
+Mnemonic: CANT
+
+Inputs:
+ - { name: "Msg", type: "dynamically" }
+
+Outputs:
+
+Parameters:
+ - { name: "Module", type: "Choice", range: "CAN1, CAN2, CAN3" }
+ - { name: "Message ID type", type: "Choice", range: "Standard, Extended" }
+ - { name: "Message ID", type: "uint16" }
+ - { name: "Automatic mailbox number", type: "bool" }
+ - { name: "Mailbox number", type: "int8" }
+
+# Description is in Markdown mark-up
+Description: |
+
+ This block allows to send a message to the CAN bus. It can be
+ configured for any of the CAN ports (modules) CAN1, CAN2 or CAN3.
+
+ The message data are read from `Msg` input port. The data type is
+ decided automatically from the input, but it is restricted to uint8,
+ uint16, uint32 and CAN\_MESSAGE. The CAN\_MESSAGE object can be
+ created by the `CAN Pack` block.
+
+ The message sent by the block will have an ID assigned according to
+ the number in the *Message ID* parameter. The block supports both
+ types of message IDs: Standard (11b) and Extended (29b). If
+ CAN\_MESSAGE is used as input type, the message ID stored in
+ CAN\_MESSAGE object is ignored and the ID from the parameter of this
+ block is used instead.
+
+ The mailbox number can be assigned automatically or manually. Automatic mailbox
+ numbers are generated in ascending order from 0 to 31. Every mailbox must have a unique
+ number. It is possible to mix blocks with automatically and manually
+ assigned mailboxes. If the manually assigned mailbox number would
+ collide with the automatic one then the automatically generated
+ block will get assigned a next higher non-colliding ID.
+ The mailbox numbers are shared between CAN Transmit and CAN Receive
+ blocks with the same CAN port (module) parameter.
+
+ In order to use this block, there must be a `CAN Configure` block in the model.
+
+Status:
+ Tested:
+ - Transmission of the message with configured ID
+ - Automatic generation of mailboxes numbers in combination with
+ manual specification in other blocks. Colliding mailbox numbers
+ are correctly handled.
+ - Input message data type recognition
+ - When unsupported data type is connected to the Msg input port, Simulink generates a reasonable error message
+ Untested:
+ - Handling of error states on CAN bus
+ Not working:
+ - External mode - throwing syntax error during compilation
+
+RPP API functions used:
+ - rpp_can_write()
+
+Relevant demos:
+ - cantransmit
+ - can_demo
+...
+*/
+
+
+#define S_FUNCTION_NAME sfunction_cantransmit
+#include "header.c"
+#include <stdio.h>
+#include "sfun_can_util.h"
+
+#define MSG_TYPE_STANDART_MAX 2048
+#define MSG_TYPE_EXTENDED_MAX 536870912
+#define MAILBOX_ID_MIN 1
+#define MAILBOX_MAX_CNT 64
+
+#define PARAM_NAME_MODULE_ID "module_id"
+#define PARAM_NAME_MAILBOX_ID "mailbox_id"
+#define PARAM_NAME_MESSAGE_TYPE "message_type"
+#define PARAM_NAME_MESSAGE_ID "message_id"
+#define PARAM_NAME_MAILBOX_AUTO "mailbox_auto"
+
+/** Identifier of the input */
+enum input {
+ IN_MSG,
+ IN_COUNT
+};
+
+/** Identifiers of the block parameters */
+enum params{
+ PARAM_MODULE_ID,
+ PARAM_MAILBOX_ID,
+ PARAM_MSG_TYPE,
+ PARAM_MSG_ID,
+ PARAM_MAILBOX_AUTO,
+ PARAM_COUNT
+};
+
+enum message_id_type {
+ MSG_ID_STANDART,
+ MSG_ID_EXTENDED,
+ MSG_ID_MIXED
+};
+
+
+static void mdlInitializeSizes(SimStruct *S)
+{
+
+ CAN_Common_MdlInitSizes(S);
+
+ if (!rppSetNumParams(S, PARAM_COUNT)) {
+ return;
+ }
+
+ /*
+ * Configure input ports: 1
+ * - Message to be sent
+ */
+ if (!ssSetNumInputPorts(S, IN_COUNT)) {
+ return;
+ }
+
+ rppAddInputPort(S, IN_MSG, DYNAMICALLY_TYPED);
+
+ /* No output ports */
+ if (!ssSetNumOutputPorts(S, 0)) {
+ return;
+ }
+
+ /* Set standard options for this block */
+ rppSetStandardOptions(S);
+}
+
+#if defined(MATLAB_MEX_FILE)
+#define MDL_SET_INPUT_PORT_DATA_TYPE
+void mdlSetInputPortDataType(SimStruct *S, int_T port, DTypeId type)
+{
+ if (port == IN_MSG) {
+ if (type == SS_UINT8 ||
+ type == SS_UINT16 ||
+ type == SS_UINT32 ||
+ /* CAN pack seems to use this data type, but it is
+ * not registered in sfun_can_util.c. Strange. */
+ type == ssGetDataTypeId(S, "CAN_MESSAGE") ||
+ type == ssGetDataTypeId(S, SL_CAN_STANDARD_FRAME_DTYPE_NAME) ||
+ type == ssGetDataTypeId(S, SL_CAN_EXTENDED_FRAME_DTYPE_NAME))
+ ssSetInputPortDataType(S, port, type);
+ else {
+ char msg[300];
+ snprintf(msg, sizeof(msg), "Unsupported data type '%s' on Msg input port.",
+ ssGetDataTypeName(S, type));
+ ssSetErrorStatus(S, msg);
+ }
+ }
+}
+#endif
+
+#ifdef MATLAB_MEX_FILE
+#define MDL_CHECK_PARAMETERS
+
+static void mdlCheckParameters(SimStruct *S){
+ /* Check the parameter mailbox id */
+ if ((int_T)mxGetPr(ssGetSFcnParam(S, PARAM_MAILBOX_AUTO))[0] == 0) {
+ if (!rppValidParamRange(S, PARAM_MAILBOX_ID, MAILBOX_ID_MIN, MAILBOX_ID_MIN + MAILBOX_MAX_CNT)) {
+ return;
+ }
+ }
+
+ int min = 0;
+ int max = 0;
+ if ((int_T)mxGetPr(ssGetSFcnParam(S, PARAM_MSG_TYPE))[0] == MSG_ID_STANDART) {
+ max = MSG_TYPE_STANDART_MAX;
+ }
+ else {
+ max = MSG_TYPE_EXTENDED_MAX;
+ }
+
+ /* Check the parameter message id */
+ if (!rppValidParamRange(S, PARAM_MSG_ID, min, max)) {
+ return;
+ }
+}
+#endif
+
+
+#ifdef MATLAB_MEX_FILE
+#define MDL_SET_WORK_WIDTHS
+static void mdlSetWorkWidths(SimStruct *S){
+
+ if (!ssSetNumRunTimeParams(S, PARAM_COUNT)) {
+ return;
+ }
+
+ ssRegDlgParamAsRunTimeParam(S, PARAM_MODULE_ID, PARAM_MODULE_ID, PARAM_NAME_MODULE_ID, SS_UINT8);
+ ssRegDlgParamAsRunTimeParam(S, PARAM_MAILBOX_ID, PARAM_MAILBOX_ID, PARAM_NAME_MAILBOX_ID, SS_INT8);
+ ssRegDlgParamAsRunTimeParam(S, PARAM_MSG_TYPE, PARAM_MSG_TYPE, PARAM_NAME_MESSAGE_TYPE, SS_UINT16);
+ ssRegDlgParamAsRunTimeParam(S, PARAM_MSG_ID, PARAM_MSG_ID, PARAM_NAME_MESSAGE_ID, SS_UINT32);
+ ssRegDlgParamAsRunTimeParam(S, PARAM_MAILBOX_AUTO, PARAM_MAILBOX_AUTO, PARAM_NAME_MAILBOX_AUTO, SS_BOOLEAN);
+}
+#endif
+
+#define COMMON_MDLINITIALIZESAMPLETIMES_INHERIT
+#define UNUSED_MDLOUTPUTS
+#define UNUSED_MDLTERMINATE
+#include "trailer.c"
--- /dev/null
+%% Redistribution and use in source and binary forms, with or without
+%% modification, are permitted provided that the following conditions are
+%% met:
+%%
+%% 1. Redistributions of source code must retain the above copyright
+%% notice, this list of conditions and the following disclaimer.
+%%
+%% 2. Redistributions in binary form must reproduce the above copyright
+%% notice, this list of conditions and the following disclaimer in the
+%% documentation and/or other materials provided with the
+%% distribution.
+%%
+%% 3. Neither the name of the copyright holder nor the names of its
+%% contributors may be used to endorse or promote products derived
+%% from this software without specific prior written permission.
+%%
+%% THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+%% "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+%% LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+%% A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+%% HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+%% SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+%% LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+%% DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+%% THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+%% (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+%% OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+%%
+%% File : common.tlc
+%% Abstract:
+%% Common functions for blocks TLCs.
+%%
+%% References:
+%% None
+
+
+%function SLibCodeGenForSim() void
+ %if (CompiledModel.TargetStyle=="SimulationTarget")
+ %return 1
+ %else
+ %return 0
+ %endif
+%endfunction
+
+
+%function RppCommonBlockTypeSetup(block, system) void
+
+ %if EXISTS("_DONE_COMMON_BLOCK_TYPE_SETUP_") == 0
+ %assign _DONE_COMMON_BLOCK_TYPE_SETUP_ = 1
+ %if !SLibCodeGenForSim()
+
+ %<LibAddToCommonIncludes("<rpp/rpp.h>")>
+ %<LibAddToCommonIncludes("can_message.h")>
+
+ %endif
+ %endif
+ %if EXISTS("::rpp_fray_buffer_config") == 0
+ %assign ::rpp_fray_buffer_config = ""
+ %endif
+ %if EXISTS("::rpp_fray_buffer_count") == 0
+ %assign ::rpp_fray_buffer_count = 0
+ %endif
+ %if EXISTS("::rpp_fray_buffer_key_slot") == 0
+ %assign ::rpp_fray_buffer_key_slot = ""
+ %endif
+%endfunction
+
--- /dev/null
+%% Copyright (C) 2014 Czech Technical University in Prague
+%%
+%% Authors:
+%% Michal Horn <hornmich@fel.cvut.cz>
+%% Michal Sojka <sojkam1@fel.cvut.cz>
+%%
+%% Redistribution and use in source and binary forms, with or without
+%% modification, are permitted provided that the following conditions are
+%% met:
+%%
+%% 1. Redistributions of source code must retain the above copyright
+%% notice, this list of conditions and the following disclaimer.
+%%
+%% 2. Redistributions in binary form must reproduce the above copyright
+%% notice, this list of conditions and the following disclaimer in the
+%% documentation and/or other materials provided with the
+%% distribution.
+%%
+%% 3. Neither the name of the copyright holder nor the names of its
+%% contributors may be used to endorse or promote products derived
+%% from this software without specific prior written permission.
+%%
+%% THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+%% "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+%% LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+%% A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+%% HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+%% SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+%% LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+%% DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+%% THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+%% (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+%% OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+%%
+%% File : rpp_can_common.tlc
+%% Abstract:
+%% TLC file with common functions and variables for sfunction_canreceive, sfunction_cansetup and sfunction_cantransmit
+%%
+%% References:
+%% Coding Convention: refs/rtw_tlc.pdf p. 58 (TODO)
+%%
+
+%% Function: RppCANCommonBlockTypeSetup ========================================
+%% Declares and initializes all common variables and constants.
+
+%function RppCANCommonBlockTypeSetup() void
+ %if EXISTS("::_RPP_MAX_MAILBOX_CNT") == 0
+ %assign ::_RPP_MAX_MAILBOX_CNT = 64
+
+ /% Global data structure used in call CAN blocks %/
+ %createrecord ::Rpp { Can { ...
+ Tx { NumBlocks 0 } ...
+ Rx { NumBlocks 0 } ...
+ }}
+
+ /% Add records for helping with message object allocation %/
+ %foreach i = 3 %% We have 3 CAN controllers
+ %addtorecord Rpp.Can Ctrl {}
+ %endforeach
+ %endif
+%endfunction
+
+%function RppCanAssignMsgObj(msgObjNum, blockInfo) void
+ %if msgObjNum < 1 || msgObjNum > ::_RPP_MAX_MAILBOX_CNT
+ %<LibBlockReportError(block, "Invalid mailbox number!")>
+ %endif
+ %addtorecord Rpp.Can.Ctrl[blockInfo.Controller-1] MsgObj%<msgObjNum>UsedBy blockInfo
+ %assign blockInfo.MsgObj = msgObjNum
+%endfunction
+
+%function RppCanGetBlockInfoFromMsgObj(module, mailbox_number)
+ %return Rpp.Can.Ctrl[module-1].MsgObj%<mailbox_number>UsedBy
+%endfunction
+
+%function RppCanIsMsgObjAssigned(module, mailbox_number)
+ %return ISFIELD(Rpp.Can.Ctrl[%<module-1>], "MsgObj%<mailbox_number>UsedBy")
+%endfunction
+
+%% Function: RppFindFreeMailboxNumber =========================================
+%% Returns the lowest possible free mailbox number or 0 if no mailbox is free.
+
+%function RppFindFreeMailboxNumber(module) void
+ %foreach mn = ::_RPP_MAX_MAILBOX_CNT + 1
+ %if mn == 0
+ %continue
+ %endif
+ %if RppCanIsMsgObjAssigned(module, mn) == 0
+ %return %<mn>
+ %endif
+ %endforeach
+ %return 0
+%endfunction
+
+%% Function: RppPlaceAutomaticMailboxNumber ===================================
+%% Assignes an automaticaly determined mailbox number for the CAN block.
+
+%function RppPlaceAutomaticMailboxNumber(blockInfo) void
+ %assign msg_obj_number = RppFindFreeMailboxNumber(blockInfo.Controller)
+ %if %<msg_obj_number> == 0
+ %<LibBlockReportError(block, "Too many blocks in one module!")>
+ %endif
+ %addtorecord blockInfo ManualMsgObj 0 /% For MsgObj collision detection %/
+ %<RppCanAssignMsgObj(msg_obj_number, blockInfo)>
+%endfunction
+
+%% Function: RppPlaceManualMailboxNumber ======================================
+
+%% Assigns a manualy specified mailbox number to the CAN blocks.
+%% Reports collisions with other manually assigned blocks and optionally
+%% reassignes mailbox numbers of previously assigned automatic blocks.
+%%
+%% Params: msg_obj_num The requested number of the mailbox.
+
+%function RppPlaceManualMailboxNumber(blockInfo, msg_obj_number) void
+ %if RppCanIsMsgObjAssigned(blockInfo.Controller, msg_obj_number)
+ %assign prevBlockInfo = RppCanGetBlockInfoFromMsgObj(blockInfo.Controller, msg_obj_number)
+ %if prevBlockInfo.ManualMsgObj
+ %<LibBlockReportError(block, "Colliding mailbox number found!")>
+ %endif
+ %assign new_msg_obj_number = RppFindFreeMailboxNumber(blockInfo.Controller)
+ %if new_msg_obj_number == 0
+ %<LibBlockReportError(block, "Too many blocks in one module!")>
+ %endif
+ %<RppCanAssignMsgObj(new_msg_obj_number, prevBlockInfo)>
+ %endif
+ %addtorecord blockInfo ManualMsgObj 1 /% For MsgObj collision detection %/
+ %<RppCanAssignMsgObj(msg_obj_number, blockInfo)>
+%endfunction
+
+%% [EOF]
--- /dev/null
+%% Copyright (C) 2014 Czech Technical University in Prague
+%%
+%% Authors:
+%% Michal Horn <hornmich@fel.cvut.cz>
+%% Michal Sojka <sojkam1@fel.cvut.cz>
+%%
+%% Redistribution and use in source and binary forms, with or without
+%% modification, are permitted provided that the following conditions are
+%% met:
+%%
+%% 1. Redistributions of source code must retain the above copyright
+%% notice, this list of conditions and the following disclaimer.
+%%
+%% 2. Redistributions in binary form must reproduce the above copyright
+%% notice, this list of conditions and the following disclaimer in the
+%% documentation and/or other materials provided with the
+%% distribution.
+%%
+%% 3. Neither the name of the copyright holder nor the names of its
+%% contributors may be used to endorse or promote products derived
+%% from this software without specific prior written permission.
+%%
+%% THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+%% "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+%% LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+%% A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+%% HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+%% SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+%% LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+%% DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+%% THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+%% (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+%% OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+%%
+%% File : sfunction_canreceive.tlc
+%% Abstract:
+%% TLC file for configuring the CAN RX buffer on the TI TMS570LS3137 MCU
+%%
+%% References:
+%% BlockTypeSetup() : refs/rtw_tlc.pdf p. 277
+%% Outputs() : refs/rtw_tlc.pdf p. 281
+
+
+%implements sfunction_canreceive "C"
+
+%include "common.tlc"
+%include "rpp_can_common.tlc"
+
+%% Function: BlockTypeSetup ====================================================
+%function BlockTypeSetup(block, system) void
+ %<RppCommonBlockTypeSetup(block, system)>
+ %<RppCANCommonBlockTypeSetup()>
+%endfunction
+
+%% Function: BlockInstanceSetup ================================================
+%function BlockInstanceSetup(block, system) void
+
+ %assign module_id_par = LibBlockParameterValue(module_id, 0)
+ %assign mailbox_num_par = LibBlockParameterValue(mailbox_id, 0)
+ %assign message_type_par = LibBlockParameterValue(message_type, 0)
+ %assign message_id_par = LibBlockParameterValue(message_id, 0)
+ %assign data_type_par = LibBlockParameterValue(data_type, 0)
+ %assign message_filter_par = LibBlockParameterValue(message_filter, 0)
+ %assign message_mask_par = LibBlockParameterValue(message_mask, 0)
+ %assign mailbox_auto_par = LibBlockParameterValue(mailbox_auto, 0)
+
+ %if message_filter_par == 1
+ %assign mask = 8388607 %% 0x7FFFFF
+ %else
+ %assign mask = message_mask_par
+ %endif
+
+ %% This seems to be the only way to add a record to an array. The
+ %% other way - creating the record with %createrecord and adding
+ %% it later with %addtorecord doesn't work.
+ %addtorecord Rpp.Can.Rx Block { ...
+ HwObj Rpp.Can.Rx.NumBlocks; ...
+ Controller module_id_par; ...
+ MsgObj 0; /% Invalid MsgObj - proper value will be assigned later %/ ...
+ Type message_type_par; ...
+ Id message_id_par; ...
+ Mask mask; ...
+ Name "%<LibGetBlockName(block)>" ...
+ }
+ %assign blockInfo = Rpp.Can.Rx.Block[Rpp.Can.Rx.NumBlocks] /% create alias to the record %/
+ %if %<mailbox_auto_par>==1
+ %<RppPlaceAutomaticMailboxNumber(blockInfo)>
+ %else
+ %<RppPlaceManualMailboxNumber(blockInfo, mailbox_num_par)>
+ %endif
+
+ /% Remember which blockInfo record is associated wit this block %/
+ %addtorecord block RppRxInfo blockInfo
+ %assign Rpp.Can.Rx.NumBlocks = Rpp.Can.Rx.NumBlocks + 1
+%endfunction
+
+%% Function: Start =============================================================
+%function Start(block, system) Output
+
+ %if !SLibCodeGenForSim()
+
+ %if EXISTS(::rpp_can_config_present) == 0
+ %<LibBlockReportError(block, "CAN buc configuration block not present!")>
+ %endif
+ %endif
+
+
+%endfunction
+
+%% Function: Outputs ===========================================================
+%function Outputs(block, system) Output
+
+ %if !SLibCodeGenForSim()
+ %assign data_type_par = LibBlockParameterValue(data_type, 0)
+ %assign message = LibBlockOutputSignal(1, "", "", 1)
+
+ {
+ struct rpp_can_pdu pdu;
+ int ret;
+
+ ret = rpp_can_read(%<RppRxInfo.HwObj>, &pdu);
+ switch (ret) {
+ case -RPP_EINVAL:
+ rpp_sci_printf("Receiving CAN message failed (%s).\n", "%<RppRxInfo.Name>");
+ break;
+ case -RPP_ENODATA:
+ break;
+ case SUCCESS: {
+ %if %<data_type_par>==4
+ // CAN_MESSAGE
+ %<message>.Length = pdu.dlc;
+ %<message>.ID = pdu.id;
+ int i;
+ for (i = 0; i < pdu.dlc; i++ ) {
+ %<message>.Data[i] = pdu.data[i];
+ %%rpp_sci_printf("%X ", pdu.data[i]);
+ }
+ %elseif %<data_type_par>==3
+ // uint32
+ int msg = (pdu.data[0]) |
+ (pdu.data[1]<<8) |
+ (pdu.data[2]<<16) |
+ (pdu.data[3]<<24);
+ %<message> = msg;
+ %%rpp_sci_printf("32b: %X ", msg);
+ %elseif %<data_type_par>==2
+ // uint16
+ int msg = (pdu.data[0]) |
+ (pdu.data[1]<<8);
+ %<message> = msg;
+ %%rpp_sci_printf("16b: %X ", msg);
+ %else
+ // uint8
+ int msg = pdu.data[0];
+ %<message> = msg;
+ %%rpp_sci_printf("8b: %X ", msg);
+ %endif
+ %%rpp_sci_printf("\n");
+
+ %% Call a function to process the received message via function-call subsystem
+ %foreach callIdx = NumSFcnSysOutputCalls
+ %if LibIsEqual(SFcnSystemOutputCall[callIdx].BlockToCall,"unconnected")
+ %continue
+ %endif
+ %% call the downstream system
+ %<LibBlockExecuteFcnCall(block, callIdx)>\
+ %endforeach
+ break;
+ }
+ }
+ }
+ %endif
+%endfunction
+
+%% [EOF]
--- /dev/null
+%% Copyright (C) 2014 Czech Technical University in Prague
+%%
+%% Authors:
+%% Michal Horn <hornmich@fel.cvut.cz>
+%% Michal Sojka <sojkam1@fel.cvut.cz>
+%%
+%% Redistribution and use in source and binary forms, with or without
+%% modification, are permitted provided that the following conditions are
+%% met:
+%%
+%% 1. Redistributions of source code must retain the above copyright
+%% notice, this list of conditions and the following disclaimer.
+%%
+%% 2. Redistributions in binary form must reproduce the above copyright
+%% notice, this list of conditions and the following disclaimer in the
+%% documentation and/or other materials provided with the
+%% distribution.
+%%
+%% 3. Neither the name of the copyright holder nor the names of its
+%% contributors may be used to endorse or promote products derived
+%% from this software without specific prior written permission.
+%%
+%% THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+%% "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+%% LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+%% A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+%% HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+%% SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+%% LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+%% DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+%% THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+%% (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+%% OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+%%
+%% File : sfunction_cansetup.tlc
+%% Abstract:
+%% TLC file for configuring the CAN modules on the TI TMS570LS3137 MCU
+%%
+%% References:
+%% BlockTypeSetup() : refs/rtw_tlc.pdf p. 277
+%% Outputs() : refs/rtw_tlc.pdf p. 281
+
+
+%implements sfunction_cansetup "C"
+
+%include "common.tlc"
+%include "rpp_can_common.tlc"
+
+%% Function: BlockTypeSetup ====================================================
+%function BlockTypeSetup(block, system) void
+
+ %% Ensure required header files are included
+ %<RppCommonBlockTypeSetup(block, system)>
+ %<LibAddToCommonIncludes("<sys/ti_drv_dmm.h>")>
+
+ %assign ::rpp_can_config_present = 1
+
+ %<RppCANCommonBlockTypeSetup()>
+%endfunction
+
+%function BlockInstanceSetup(block, system) void
+ %if EXISTS("rpp_canc_in_model") == 0
+ %assign ::rpp_canc_in_model = 1
+ %else
+ %<LibBlockReportError(block, "Only one CAN Setup block is allowed in the model.")>
+ %endif
+%endfunction
+
+
+%% Function: Start =============================================================
+%function Start(block, system) Output
+ %openfile buffer
+
+ #define CAN_TX_COUNT %<Rpp.Can.Tx.NumBlocks>
+ #define CAN_RX_COUNT %<Rpp.Can.Rx.NumBlocks>
+
+ struct rpp_can_ctrl_config can_ctrl_cfg[3] = {
+ {
+ .baudrate = %<LibBlockParameterValue(baudrate_can1, 0)>
+ },
+ {
+ .baudrate = %<LibBlockParameterValue(baudrate_can2, 0)>
+ },
+ {
+ .baudrate = %<LibBlockParameterValue(baudrate_can3, 0)>
+ }
+ };
+
+ struct rpp_can_tx_config tx_config[CAN_TX_COUNT] = {
+ %foreach id = Rpp.Can.Tx.NumBlocks
+ %with Rpp.Can.Tx.Block[id]
+ // %<Name>
+ {
+ %if %<Type> == 1
+ .type = RPP_CAN_STANDARD,
+ %elseif %<Type> == 2
+ .type = RPP_CAN_EXTENDED,
+ %else
+ .type = RPP_CAN_MIXED,
+ %endif
+ .controller = %<Controller>,
+ .msg_obj = %<MsgObj>
+ },
+ %endwith
+ %endforeach
+ };
+
+ struct rpp_can_rx_config rx_config[CAN_RX_COUNT] = {
+ %foreach id = Rpp.Can.Rx.NumBlocks
+ %with Rpp.Can.Rx.Block[id]
+ // %<Name>
+ {
+ %if %<Type>==1
+ .type = RPP_CAN_STANDARD,
+ %elseif %<Type>==2
+ .type = RPP_CAN_EXTENDED,
+ %else
+ .type = RPP_CAN_MIXED,
+ %endif
+ .controller = %<Controller>,
+ .msg_obj = %<MsgObj>,
+ .id = %<Id>,
+ .mask = %<SPRINTF("%#x", Mask)>
+ },
+ %endwith
+ %endforeach
+ };
+
+ const struct rpp_can_config can_config = {
+ .num_tx_obj = CAN_TX_COUNT,
+ .num_rx_obj = CAN_RX_COUNT,
+ .tx_config = tx_config,
+ .rx_config = rx_config,
+ .ctrl = can_ctrl_cfg
+ };
+
+ %closefile buffer
+ %<LibSetSourceFileSection(LibGetModelDotCFile(), "Declarations", buffer)>
+ int returnstatus;
+
+ dmmREG->PC4 = 1<<13; // set CAN_NSTB
+ dmmREG->PC5 = 1<<15; // clr CAN_EN
+ dmmREG->PC5 = 1<<13; // clr CAN_NSTB
+ dmmREG->PC4 = 1<<13; // set CAN_NSTB
+ dmmREG->PC4 = 1<<15; // set CAN_EN
+
+ returnstatus = rpp_can_init(&can_config);
+ if (returnstatus == FAILURE) {
+ rpp_sci_printf("CAN driver initialization error.\n");
+ }
+ %%else {
+ %% rpp_sci_printf("CAN communication initialized.\n");
+ %%}
+ %endfunction
+
+%% [EOF]
--- /dev/null
+%% Copyright (C) 2014 Czech Technical University in Prague
+%%
+%% Authors:
+%% Michal Horn <hornmich@fel.cvut.cz>
+%% Michal Sojka <sojkam1@fel.cvut.cz>
+%%
+%% Redistribution and use in source and binary forms, with or without
+%% modification, are permitted provided that the following conditions are
+%% met:
+%%
+%% 1. Redistributions of source code must retain the above copyright
+%% notice, this list of conditions and the following disclaimer.
+%%
+%% 2. Redistributions in binary form must reproduce the above copyright
+%% notice, this list of conditions and the following disclaimer in the
+%% documentation and/or other materials provided with the
+%% distribution.
+%%
+%% 3. Neither the name of the copyright holder nor the names of its
+%% contributors may be used to endorse or promote products derived
+%% from this software without specific prior written permission.
+%%
+%% THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+%% "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+%% LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+%% A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+%% HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+%% SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+%% LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+%% DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+%% THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+%% (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+%% OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+%%
+%% File : sfunction_cantransmit.tlc
+%% Abstract:
+%% TLC file for configuring the CAN TX buffer on the TI TMS570LS3137 MCU
+%%
+%% References:
+%% BlockTypeSetup() : refs/rtw_tlc.pdf p. 277
+%% Outputs() : refs/rtw_tlc.pdf p. 281
+
+
+%implements sfunction_cantransmit "C"
+
+%include "common.tlc"
+%include "rpp_can_common.tlc"
+
+%% Function: BlockTypeSetup ====================================================
+%function BlockTypeSetup(block, system) void
+ %<RppCommonBlockTypeSetup(block, system)>
+ %<RppCANCommonBlockTypeSetup()>
+%endfunction
+
+%% Function: BlockInstanceSetup ================================================
+%function BlockInstanceSetup(block, system) void
+ %assign module_id_par = LibBlockParameterValue(module_id, 0)
+ %assign mailbox_num_par = LibBlockParameterValue(mailbox_id, 0)
+ %assign message_type_par = LibBlockParameterValue(message_type, 0)
+ %assign message_id_par = LibBlockParameterValue(message_id, 0)
+ %assign mailbox_auto_par = LibBlockParameterValue(mailbox_auto, 0)
+
+ %% This seems to be the only way to add a record to an array. The
+ %% other way - creating the record with %createrecord and adding
+ %% it later with %addtorecord doesn't work.
+ %addtorecord Rpp.Can.Tx Block { ...
+ HwObj Rpp.Can.Tx.NumBlocks; ...
+ Controller module_id_par; ...
+ MsgObj 0; /% Invalid MsgObj - proper value will be assigned later %/ ...
+ Type message_type_par; ...
+ Id message_id_par; ...
+ Name "%<LibGetBlockName(block)>" ...
+ }
+ %assign blockInfo = Rpp.Can.Tx.Block[Rpp.Can.Tx.NumBlocks] /% create alias to the record %/
+ %if %<mailbox_auto_par>==1
+ %<RppPlaceAutomaticMailboxNumber(blockInfo)>
+ %else
+ %<RppPlaceManualMailboxNumber(blockInfo, mailbox_num_par)>
+ %endif
+
+ /% Remember which blockInfo record is associated wit this block %/
+ %addtorecord block RppTxInfo blockInfo
+ %assign Rpp.Can.Tx.NumBlocks = Rpp.Can.Tx.NumBlocks + 1
+%endfunction
+
+%% Function: Start =============================================================
+%function Start(block, system) Output
+
+ %if !SLibCodeGenForSim()
+ %if EXISTS(::rpp_can_config_present) == 0
+ %<LibBlockReportError(block, "CAN bus configuration block not present!")>
+ %endif
+ %endif
+
+
+%endfunction
+
+%% Function: Outputs ===========================================================
+%function Outputs(block, system) Output
+ %if !SLibCodeGenForSim()
+ %assign message = LibBlockInputSignal(0, "", "", 0)
+ %assign msginput_data_type = LibBlockInputSignalDataTypeId(0)
+
+ {
+ struct rpp_can_pdu pdu;
+
+ %if %<msginput_data_type>==3
+ // Transmit uint8
+ pdu.dlc = 1;
+ pdu.data[0]= %<message>;
+
+ %elseif %<msginput_data_type>==5
+ // Transmit uint16
+ pdu.dlc = 2;
+ pdu.data[0]= (%<message>&0xFF);
+ pdu.data[1]= (%<message>&0xFF00)>>8;
+ %elseif %<msginput_data_type>==7
+ // Transmit uint32
+ pdu.dlc = 4;
+ pdu.data[0]= (%<message>&0xFF);
+ pdu.data[1]= (%<message>&0xFF00)>>8;
+ pdu.data[2]= (%<message>&0xFF0000)>>16;
+ pdu.data[3]= (%<message>&0xFF000000)>>24;
+ %else
+ // Transmit CAN_MESSAGE
+ pdu.dlc = %<message>.Length;
+ %foreach msg_index = 8
+ pdu.data[%<msg_index>]= %<message>.Data[%<msg_index>];
+ %endforeach
+ %endif
+ pdu.id=%<RppTxInfo.Id>;
+
+
+ %%rpp_sci_printf("CAN%d (hw_obj: %d): Sending message id 0x%X from mailbox %d. Data: ", %<module_id_par>, %<::rpp_can_tx_hw_obj_cnt>, pdu.id, %<mailbox_num_par>);
+ %%for (i = 0; i < pdu.dlc; i++ ) {
+ %% rpp_sci_printf("%X ", pdu.data[i]);
+ %%}
+ %%rpp_sci_printf("\n");
+ if (rpp_can_write(%<RppTxInfo.HwObj>, &pdu) != SUCCESS) {
+ /% rpp_sci_printf("CAN%d (hw_obj: %d): Sending a message id 0x%X from mailbox %d failed.\n", %<module_id_par>, %<::rpp_can_tx_hw_obj_cnt>, pdu.id, %<mailbox_num_par>); %/
+ }
+ }
+ %endif
+ %endfunction
+
+ %% [EOF]
--- /dev/null
+/* Copyright (C) 2013 Czech Technical University in Prague
+ *
+ * Authors:
+ * - Carlos Jenkins <carlos@jenkins.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are
+ * met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ *
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the
+ * distribution.
+ *
+ * 3. Neither the name of the copyright holder nor the names of its
+ * contributors may be used to endorse or promote products derived
+ * from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+ * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+ * HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+ * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+ * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+ * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+ * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ * File : trailer.c
+ * Abstract:
+ * Common trailer for all RPP S-Functions.
+ *
+ * References:
+ * header.c
+ */
+
+
+#ifndef S_FUNCTION_NAME
+#error 'Please include this file inside an S-Function implementation.'
+#endif
+
+
+/* Function: mdlInitializeSizes ================================================
+ * Abstract:
+ * The sizes information is used by Simulink to determine the S-function
+ * block's characteristics (number of inputs, outputs, states, etc.).
+ */
+#ifdef UNUSED_MDLINITIALIZESIZES
+static void mdlInitializeSizes(SimStruct *S)
+{
+ UNUSED_PARAMETER(S);
+}
+#endif
+
+
+/* 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.
+ */
+#ifdef UNUSED_MDLINITIALIZESAMPLETIMES
+static void mdlInitializeSampleTimes(SimStruct *S)
+{
+ UNUSED_PARAMETER(S);
+}
+#endif
+
+
+#ifdef COMMON_MDLINITIALIZESAMPLETIMES_INHERIT
+static void mdlInitializeSampleTimes(SimStruct *S)
+{
+ ssSetSampleTime(S, 0, INHERITED_SAMPLE_TIME);
+ ssSetOffsetTime(S, 0, 0.0);
+ #if defined(ssSetModelReferenceSampleTimeDefaultInheritance)
+ ssSetModelReferenceSampleTimeDefaultInheritance(S);
+ #endif
+}
+#endif
+
+
+/* Function: mdlOutputs ========================================================
+ * Abstract:
+ * In this function, you compute the outputs of your S-function
+ * block. Generally outputs are placed in the output vector(s),
+ * ssGetOutputPortSignal.
+ */
+#ifdef UNUSED_MDLOUTPUTS
+static void mdlOutputs(SimStruct *S, int_T tid)
+{
+ UNUSED_PARAMETER(S);
+ UNUSED_PARAMETER(tid);
+}
+#endif
+
+
+/* Function: mdlTerminate ======================================================
+ * Abstract:
+ * In this function, you should perform any actions that are necessary
+ * at the termination of a simulation.
+ */
+#ifdef UNUSED_MDLTERMINATE
+static void mdlTerminate(SimStruct *S)
+{
+ UNUSED_PARAMETER(S);
+}
+#endif
+
+
+/* Function: mdlCheckParameters ================================================
+ * Abstract:
+ * mdlCheckParameters verifies new parameter settings whenever parameter
+ * change or are re-evaluated during a simulation. When a simulation is
+ * running, changes to S-function parameters can occur at any time during
+ * the simulation loop.
+ *
+ * Note: this an optional function for S-Function, in contrast to the ones
+ * above. This is here just because header.c declares
+ * checkParametersMismatch() that uses this function in order to
+ * refactor that commonly used block of code.
+ */
+#ifdef UNUSED_MDLCHECKPARAMETERS
+static void mdlCheckParameters(SimStruct *S)
+{
+ UNUSED_PARAMETER(S);
+}
+#endif
+
+
+/*
+ * Required S-function trailer
+ */
+#ifdef MATLAB_MEX_FILE
+# include "simulink.c"
+#else
+# include "cg_sfun.h"
+#endif
+