dispatch.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2018-2019, Dataspeed Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Dataspeed Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 #ifndef _DBW_FCA_CAN_DISPATCH_H
00036 #define _DBW_FCA_CAN_DISPATCH_H
00037 #include <stdint.h>
00038 
00039 namespace dbw_fca_can
00040 {
00041 
00042 typedef struct {
00043   uint16_t PCMD;
00044   uint8_t :4;
00045   uint8_t CMD_TYPE :4;
00046   uint8_t EN :1;
00047   uint8_t CLEAR :1;
00048   uint8_t IGNORE :1;
00049   uint8_t :4;
00050   uint8_t RES1 :1;
00051   uint8_t :8;
00052   uint8_t :8;
00053   uint8_t :8;
00054   uint8_t COUNT;
00055 } MsgBrakeCmd;
00056 
00057 typedef struct {
00058   uint16_t PI;
00059   uint16_t PC;
00060   uint16_t PO;
00061   uint8_t BTYPE :1;
00062   uint8_t :2;
00063   uint8_t WDCBRK :1;
00064   uint8_t WDCSRC :4;
00065   uint8_t ENABLED :1;
00066   uint8_t OVERRIDE :1;
00067   uint8_t DRIVER :1;
00068   uint8_t FLTWDC :1;
00069   uint8_t FLT1 :1;
00070   uint8_t FLT2 :1;
00071   uint8_t FLTPWR :1;
00072   uint8_t TMOUT :1;
00073 } MsgBrakeReport;
00074 
00075 typedef struct {
00076   uint16_t PCMD;
00077   uint8_t :4;
00078   uint8_t CMD_TYPE :4;
00079   uint8_t EN :1;
00080   uint8_t CLEAR :1;
00081   uint8_t IGNORE :1;
00082   uint8_t :4;
00083   uint8_t RES1 :1;
00084   uint8_t :8;
00085   uint8_t :8;
00086   uint8_t :8;
00087   uint8_t COUNT;
00088 } MsgThrottleCmd;
00089 
00090 typedef struct {
00091   uint16_t PI;
00092   uint16_t PC;
00093   uint16_t PO;
00094   uint8_t :4;
00095   uint8_t WDCSRC :4;
00096   uint8_t ENABLED :1;
00097   uint8_t OVERRIDE :1;
00098   uint8_t DRIVER :1;
00099   uint8_t FLTWDC :1;
00100   uint8_t FLT1 :1;
00101   uint8_t FLT2 :1;
00102   uint8_t FLTPWR :1;
00103   uint8_t TMOUT :1;
00104 } MsgThrottleReport;
00105 
00106 typedef struct {
00107   int16_t SCMD;
00108   uint8_t EN :1;
00109   uint8_t CLEAR :1;
00110   uint8_t IGNORE :1;
00111   uint8_t :1;
00112   uint8_t QUIET :1;
00113   uint8_t :2;
00114   uint8_t CMD_TYPE :1;
00115   uint8_t SVEL;
00116   uint8_t :8;
00117   uint8_t :8;
00118   uint8_t :8;
00119   uint8_t COUNT;
00120 } MsgSteeringCmd;
00121 
00122 typedef struct {
00123   int16_t ANGLE;
00124   int16_t CMD :15;
00125   uint8_t TMODE :1; // Torque mode
00126   uint16_t SPEED;
00127   int8_t TORQUE;
00128   uint8_t ENABLED :1;
00129   uint8_t OVERRIDE :1;
00130   uint8_t FLTPWR :1;
00131   uint8_t FLTWDC :1;
00132   uint8_t FLTBUS1 :1;
00133   uint8_t FLTBUS2 :1;
00134   uint8_t FLTCAL :1;
00135   uint8_t TMOUT :1;
00136 } MsgSteeringReport;
00137 
00138 typedef struct {
00139   uint8_t GCMD :3;
00140   uint8_t :4;
00141   uint8_t CLEAR :1;
00142 } MsgGearCmd;
00143 
00144 typedef struct {
00145   uint8_t STATE :3;
00146   uint8_t OVERRIDE :1;
00147   uint8_t CMD :3;
00148   uint8_t FLTBUS :1;
00149   uint8_t REJECT :3;
00150   uint8_t :5;
00151 } MsgGearReport;
00152 
00153 typedef struct {
00154   uint8_t TRNCMD :2;
00155   uint8_t :6;
00156 } MsgTurnSignalCmd;
00157 
00158 typedef struct {
00159   uint8_t turn_signal :2;
00160   uint8_t :6;
00161   uint8_t :3;
00162   uint8_t :1;
00163   uint8_t :1;
00164   uint8_t btn_cc_res :1;
00165   uint8_t btn_cc_cncl :1;
00166   uint8_t :1;
00167   uint8_t btn_cc_on_off :1;
00168   uint8_t :1;
00169   uint8_t btn_cc_set_inc :1;
00170   uint8_t btn_cc_set_dec :1;
00171   uint8_t btn_cc_gap_inc :1;
00172   uint8_t btn_cc_gap_dec :1;
00173   uint8_t :1;
00174   uint8_t FLTBUS :1;
00175   uint8_t :8;
00176   uint8_t :2;
00177   uint8_t btn_ld_ok :1;
00178   uint8_t btn_ld_up :1;
00179   uint8_t btn_ld_down :1;
00180   uint8_t btn_ld_left :1;
00181   uint8_t btn_ld_right :1;
00182   uint8_t :1;
00183   uint8_t btn_cc_mode :1;
00184   uint8_t :7;
00185 } MsgMiscReport;
00186 
00187 typedef struct {
00188   int16_t front_left;
00189   int16_t front_right;
00190   int16_t rear_left;
00191   int16_t rear_right;
00192 } MsgReportWheelSpeed;
00193 
00194 typedef struct {
00195   int16_t front_left;
00196   int16_t front_right;
00197   int16_t rear_left;
00198   int16_t rear_right;
00199 } MsgReportWheelPosition;
00200 
00201 typedef struct {
00202   int16_t  fuel_level :11;    // 0.18696 %
00203   uint8_t :5;
00204   uint8_t :8;
00205   uint8_t  battery_12v :8;    // 0.0625 V
00206   uint32_t odometer :24;      // 0.1 km
00207   uint8_t :8;
00208 } MsgReportFuelLevel;
00209 
00210 typedef struct {
00211   uint32_t brake_torque_request :12;
00212   uint32_t brake_torque_actual :12;
00213   uint32_t brake_pc :8;
00214   uint32_t brake_pressure :11;
00215   uint32_t stationary :1;
00216   uint32_t :4;
00217   uint32_t :16;
00218 } MsgReportBrakeInfo;
00219 
00220 typedef struct {
00221   int16_t axle_torque :15;
00222   int16_t :1;
00223   uint8_t throttle_pc :8;
00224   uint8_t :8;
00225   uint8_t :8;
00226   uint8_t :8;
00227   uint8_t :8;
00228   uint8_t :8;
00229 } MsgReportThrottleInfo;
00230 
00231 typedef enum {
00232   LIC_MUX_F0 = 0x00, // Feature 0 (Main)
00233   LIC_MUX_MAC   = 0x80,
00234   LIC_MUX_DATE0 = 0x81,
00235   LIC_MUX_DATE1 = 0x82,
00236   LIC_MUX_VIN0  = 0x83,
00237   LIC_MUX_VIN1  = 0x84,
00238   LIC_MUX_VIN2  = 0x85,
00239 } LicenseMux;
00240 typedef struct {
00241   uint8_t mux;
00242   uint8_t ready :1;
00243   uint8_t trial :1;
00244   uint8_t expired :1;
00245   uint8_t :5;
00246   union {
00247     struct {
00248       uint8_t enabled :1;
00249       uint8_t trial :1;
00250       uint8_t :6;
00251       uint8_t :8;
00252       uint16_t trials_used;
00253       uint16_t trials_left;
00254     } license;
00255     struct {
00256       uint8_t addr0;
00257       uint8_t addr1;
00258       uint8_t addr2;
00259       uint8_t addr3;
00260       uint8_t addr4;
00261       uint8_t addr5;
00262     } mac;
00263     struct {
00264       uint8_t date0;
00265       uint8_t date1;
00266       uint8_t date2;
00267       uint8_t date3;
00268       uint8_t date4;
00269       uint8_t date5;
00270     } date0;
00271     struct {
00272       uint8_t date6;
00273       uint8_t date7;
00274       uint8_t date8;
00275       uint8_t date9;
00276       uint8_t :8;
00277       uint8_t :8;
00278     } date1;
00279     struct {
00280       uint8_t vin00;
00281       uint8_t vin01;
00282       uint8_t vin02;
00283       uint8_t vin03;
00284       uint8_t vin04;
00285       uint8_t vin05;
00286     } vin0;
00287     struct {
00288       uint8_t vin06;
00289       uint8_t vin07;
00290       uint8_t vin08;
00291       uint8_t vin09;
00292       uint8_t vin10;
00293       uint8_t vin11;
00294     } vin1;
00295     struct {
00296       uint8_t vin12;
00297       uint8_t vin13;
00298       uint8_t vin14;
00299       uint8_t vin15;
00300       uint8_t vin16;
00301       uint8_t :8;
00302     } vin2;
00303   };
00304 } MsgLicense;
00305 
00306 typedef struct {
00307   uint8_t module;
00308   uint8_t platform;
00309   uint16_t major;
00310   uint16_t minor;
00311   uint16_t build;
00312 } MsgVersion;
00313 
00314 #define BUILD_ASSERT(cond) do { (void) sizeof(char [1 - 2*!(cond)]); } while(0)
00315 static void dispatchAssertSizes() {
00316   BUILD_ASSERT(8 == sizeof(MsgBrakeCmd));
00317   BUILD_ASSERT(8 == sizeof(MsgBrakeReport));
00318   BUILD_ASSERT(8 == sizeof(MsgThrottleCmd));
00319   BUILD_ASSERT(8 == sizeof(MsgThrottleReport));
00320   BUILD_ASSERT(8 == sizeof(MsgSteeringCmd));
00321   BUILD_ASSERT(8 == sizeof(MsgSteeringReport));
00322   BUILD_ASSERT(1 == sizeof(MsgGearCmd));
00323   BUILD_ASSERT(2 == sizeof(MsgGearReport));
00324   BUILD_ASSERT(1 == sizeof(MsgTurnSignalCmd));
00325   BUILD_ASSERT(6 == sizeof(MsgMiscReport));
00326   BUILD_ASSERT(8 == sizeof(MsgReportWheelSpeed));
00327   BUILD_ASSERT(8 == sizeof(MsgReportWheelPosition));
00328   BUILD_ASSERT(8 == sizeof(MsgReportFuelLevel));
00329   BUILD_ASSERT(8 == sizeof(MsgReportBrakeInfo));
00330   BUILD_ASSERT(8 == sizeof(MsgReportThrottleInfo));
00331   BUILD_ASSERT(8 == sizeof(MsgLicense));
00332   BUILD_ASSERT(8 == sizeof(MsgVersion));
00333 }
00334 #undef BUILD_ASSERT
00335 
00336 enum {
00337   ID_BRAKE_CMD              = 0x060,
00338   ID_BRAKE_REPORT           = 0x061,
00339   ID_THROTTLE_CMD           = 0x062,
00340   ID_THROTTLE_REPORT        = 0x063,
00341   ID_STEERING_CMD           = 0x064,
00342   ID_STEERING_REPORT        = 0x065,
00343   ID_GEAR_CMD               = 0x066,
00344   ID_GEAR_REPORT            = 0x067,
00345   ID_MISC_CMD               = 0x068,
00346   ID_MISC_REPORT            = 0x069,
00347   ID_REPORT_WHEEL_SPEED     = 0x06A,
00348   ID_REPORT_WHEEL_POSITION  = 0x070,
00349   ID_REPORT_FUEL_LEVEL      = 0x072,
00350   ID_REPORT_BRAKE_INFO      = 0x074,
00351   ID_REPORT_THROTTLE_INFO   = 0x075,
00352   ID_LICENSE                = 0x07E,
00353   ID_VERSION                = 0x07F,
00354 };
00355 
00356 } // namespace dbw_fca_can
00357 
00358 #endif // _DBW_FCA_CAN_DISPATCH_H
00359 


dbw_fca_can
Author(s): Kevin Hallenbeck
autogenerated on Sat May 4 2019 02:40:31