dispatch.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2017-2018, 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 _DATASPEED_PDS_CAN_DISPATCH_H
00036 #define _DATASPEED_PDS_CAN_DISPATCH_H
00037 #include <stdint.h>
00038 
00039 namespace dataspeed_pds_can
00040 {
00041 
00042 typedef struct {
00043   // Master and slave status messages have the same structure.
00044   // 4 Reserved/Unused bits.
00045   uint8_t :4;
00046   // Inverter Last Request (bool)
00047   uint8_t inverter_request :1;
00048   // Inverter Status (bool)
00049   uint8_t inverter_status :1;
00050   // Inverter Overloading (bool)
00051   uint8_t inverter_overload :1;
00052   // Inverter Over Temperature (bool)
00053   uint8_t inverter_overtemp :1;
00054   // Mode (enum)
00055   //   The current mode of the PDS.
00056   uint8_t mode :4;
00057   // Script (enum)
00058   //   The currently running script on the PDS, if any.
00059   uint8_t script :4;
00060   // Channel Status X (enum)
00061   //   The current status of channel X on the PDS.
00062   // Union for master channels 1-12 and slave channels 13-24
00063   union { struct {uint8_t status_01 :4; uint8_t status_02 :4;}; struct {uint8_t status_13 :4; uint8_t status_14 :4;}; };
00064   union { struct {uint8_t status_03 :4; uint8_t status_04 :4;}; struct {uint8_t status_15 :4; uint8_t status_16 :4;}; };
00065   union { struct {uint8_t status_05 :4; uint8_t status_06 :4;}; struct {uint8_t status_17 :4; uint8_t status_18 :4;}; };
00066   union { struct {uint8_t status_07 :4; uint8_t status_08 :4;}; struct {uint8_t status_19 :4; uint8_t status_20 :4;}; };
00067   union { struct {uint8_t status_09 :4; uint8_t status_10 :4;}; struct {uint8_t status_21 :4; uint8_t status_22 :4;}; };
00068   union { struct {uint8_t status_11 :4; uint8_t status_12 :4;}; struct {uint8_t status_23 :4; uint8_t status_24 :4;}; };
00069 } MsgStatus1;
00070 
00071 typedef struct {
00072   // Master and slave status messages have the same structure.
00073   // Board Temperature (float32)
00074   //   Internal board temperature, in Celsius.
00075   int8_t board_temp;
00076   // Thermocouple Temperature (float32)
00077   //   Thermocouple temperature, in Celsius.
00078   int8_t thermocouple_temp;
00079   // Voltage (float32)
00080   //   Voltage, in V.
00081   uint16_t voltage :12;
00082   // 4 Reserved/Unused bits.
00083   uint8_t :4;
00084 } MsgStatus2;
00085 
00086 typedef struct {
00087   // Union for multiple messages with the same structure: Current1Master, Current2Master, Current3Master, Current1Slave, Current2Slave, Current3Slave
00088   union { int16_t current_01; int16_t current_05; int16_t current_09; int16_t current_13; int16_t current_17; int16_t current_21; };
00089   union { int16_t current_02; int16_t current_06; int16_t current_10; int16_t current_14; int16_t current_18; int16_t current_22; };
00090   union { int16_t current_03; int16_t current_07; int16_t current_11; int16_t current_15; int16_t current_19; int16_t current_23; };
00091   union { int16_t current_04; int16_t current_08; int16_t current_12; int16_t current_16; int16_t current_20; int16_t current_24; };
00092 } MsgCurrent;
00093 
00094 typedef struct {
00095   uint8_t channel;
00096   uint8_t request;
00097 } MsgRelay;
00098 
00099 typedef struct {
00100   uint8_t mode;
00101 } MsgMode;
00102 
00103 typedef struct {
00104   uint8_t script;
00105 } MsgScript;
00106 
00107 #define BUILD_ASSERT(cond) do { (void) sizeof(char [1 - 2*!(cond)]); } while(0)
00108 static void dispatchAssertSizes() {
00109   BUILD_ASSERT(8 == sizeof(MsgCurrent));
00110   BUILD_ASSERT(8 == sizeof(MsgStatus1));
00111   BUILD_ASSERT(4 == sizeof(MsgStatus2));
00112   BUILD_ASSERT(2 == sizeof(MsgRelay));
00113   BUILD_ASSERT(1 == sizeof(MsgMode));
00114   BUILD_ASSERT(1 == sizeof(MsgScript));
00115 }
00116 #undef BUILD_ASSERT
00117 
00118 enum {
00119   ID_REQUEST   = 0x410,
00120   ID_MODE      = 0x411,
00121   ID_SCRIPT    = 0x412,
00122   ID_RESERVED1 = 0x413,
00123   ID_RESERVED2 = 0x430,
00124   ID_RESERVED3 = 0x431,
00125   ID_RESERVED4 = 0x432,
00126   ID_STATUS1_MASTER  = 0x420,
00127   ID_STATUS1_SLAVE1  = 0x421,
00128   ID_STATUS1_SLAVE2  = 0x422,
00129   ID_STATUS1_SLAVE3  = 0x423,
00130   ID_CURRENT1_MASTER = 0x424,
00131   ID_CURRENT1_SLAVE1 = 0x425,
00132   ID_CURRENT1_SLAVE2 = 0x426,
00133   ID_CURRENT1_SLAVE3 = 0x427,
00134   ID_CURRENT2_MASTER = 0x428,
00135   ID_CURRENT2_SLAVE1 = 0x429,
00136   ID_CURRENT2_SLAVE2 = 0x42A,
00137   ID_CURRENT2_SLAVE3 = 0x42B,
00138   ID_CURRENT3_MASTER = 0x42C,
00139   ID_CURRENT3_SLAVE1 = 0x42D,
00140   ID_CURRENT3_SLAVE2 = 0x42E,
00141   ID_CURRENT3_SLAVE3 = 0x42F,
00142   ID_STATUS2_MASTER  = 0x43C,
00143   ID_STATUS2_SLAVE1  = 0x43D,
00144   ID_STATUS2_SLAVE2  = 0x43E,
00145   ID_STATUS2_SLAVE3  = 0x43F,
00146 };
00147 
00148 } //namespace dataspeed_pds_can
00149 
00150 #endif // _DATASPEED_PDS_CAN_DISPATCH_H


dataspeed_pds_can
Author(s): Kevin Hallenbeck , Eric Myllyoja
autogenerated on Thu Apr 4 2019 02:42:49