Browse Source

1、完成OBD数据解析与发送 2、完成can数据通过ROS话题发布

limengqi 4 years ago
parent
commit
635df72bae

+ 0 - 2
src/canbus/CMakeLists.txt

@@ -216,8 +216,6 @@ add_executable(canbus
     candatatype.h
     messagecoder.h
     messagecoder.cpp
-    ../protobuf/CanData.pb.h
-    ../protobuf/CanData.pb.cc
  )
 
 

+ 42 - 18
src/canbus/canbus.cpp

@@ -7,8 +7,8 @@
 #include "canbus.h"
 #include"candatatype.h"
 #include"messagecoder.h"
-#include"../protobuf/CanData.pb.h"
-
+#include"../common/messagetopics.h"
+#include "std_msgs/String.h"
 
 namespace  robot{
 namespace canbus {
@@ -46,6 +46,7 @@ int Canbus::Init() {
 
   //initialize the VehHBrkStat as Hold
   status1.uiVehHBrkStat = 1;
+  LOG(INFO)<<Name()<<" init end.";
   return ROBOT_SUCCESS;
 }
 
@@ -119,7 +120,6 @@ int Canbus::read_loop()
 {
     TPCANRdMsg msg;
     __u32 status;
-    TPCANMsg canMsg;
 
     if (funLINUX_CAN_Read(pcan_handle, &msg)) {
         LOG(ERROR)<<Name()<<"receive: LINUX_CAN_Read() error.";
@@ -134,36 +134,60 @@ int Canbus::read_loop()
             LOG(ERROR)<<Name()<<"receive: CAN_Status() error";
             return errno;
         }
-        canMsg = msg.Msg;
-        read_data(&canMsg);
         LOG(INFO)<<Name()<<"receive: pending CAN status "<<(__u16)status<<" read.";
+        read_data(&(msg.Msg));
     }
     return ROBOT_SUCCESS;
 }
 
 int Canbus::read_data(TPCANMsg *pMsgBuff)
 {
-    if(pMsgBuff->ID == 0x6F1)
+    if(pMsgBuff->ID == 0x1A1)
+    {
+       T_OBD_ACC_PSNG tOBDAccPsng = *((T_OBD_ACC_PSNG*)MessageCoder::CanMsgAnalyse(0x1A1,pMsgBuff->DATA));
+       status1.uiAccPsng = tOBDAccPsng.obdAccPsng;
+    }
+    else if(pMsgBuff->ID == 0x0F1)
+    {
+       T_OBD_BRK_PSNG tOBDBrkPsng = *((T_OBD_BRK_PSNG*)MessageCoder::CanMsgAnalyse(0x0F1,pMsgBuff->DATA));
+       status1.uiBrkPsng = tOBDBrkPsng.obdBrkPsng;
+    }
+    else if(pMsgBuff->ID == 0x135)
+    {
+       T_OBD_SFT_PSNG tOBDSftPsng = *((T_OBD_SFT_PSNG*)MessageCoder::CanMsgAnalyse(0x135,pMsgBuff->DATA));
+       status1.uiSftPsng = tOBDSftPsng.obdSftPsng;
+    }
+    else if(pMsgBuff->ID == 0x1F1)
+    {
+        T_OBD_VEH_BRK_STAT tOBDVehBrkStat = *((T_OBD_VEH_BRK_STAT*)MessageCoder::CanMsgAnalyse(0x1F1,pMsgBuff->DATA));
+        status1.uiVehHBrkStat = tOBDVehBrkStat.obdVehHBrkStat;
+    }
+    else if(pMsgBuff->ID == 0x121)
     {
-      // T_VEHICLE_STATUS_1 status1 = *((T_VEHICLE_STATUS_1*)MessageCoder::CanMsgAnalyse(0x6F1,pMsgBuff->DATA));
+        T_OBD_VEH_SW_STAT tOBDVehSwStat = *((T_OBD_VEH_SW_STAT*)MessageCoder::CanMsgAnalyse(0x121,pMsgBuff->DATA));
+        status1.uiVehSwStat = tOBDVehSwStat.obdVehSwStat;
     }
-    else if(pMsgBuff->ID == 0x6F2)
+    else if(pMsgBuff->ID == 0x1E5)
     {
-       // T_VEHICLE_STATUS_2 status2 = *((T_VEHICLE_STATUS_2*)MessageCoder::CanMsgAnalyse(0x6F2,pMsgBuff->DATA));
+        T_OBD_STR_ANG tOBDStrAng = *((T_OBD_STR_ANG*)MessageCoder::CanMsgAnalyse(0x1E5,pMsgBuff->DATA));
+        status2.iStrAng = tOBDStrAng.obdStrAng;
     }
-    else if(pMsgBuff->ID == 0x6F3)
+    else if(pMsgBuff->ID == 0x0C9)
     {
-      //  T_VEHICLE_STATUS_3 status3 = *((T_VEHICLE_STATUS_3*)MessageCoder::CanMsgAnalyse(0x6F3,pMsgBuff->DATA));
+        T_OBD_ENG_SPD tOBDEngSpd = *((T_OBD_ENG_SPD*)MessageCoder::CanMsgAnalyse(0x0C9,pMsgBuff->DATA));
+        status2.uiEngSpd = tOBDEngSpd.obdEngSpd;
     }
     else
     {
-        //ToDo:throw decision
-      dataAnalysis::CanData canData;
-      canData.set_id(pMsgBuff->ID);
-      canData.set_data(reinterpret_cast<const char*>(pMsgBuff->DATA));
-      //ros::NodeHandle n;
-      //ros::Publisher pub = n.advertise<dataAnalysis::CanData>("canDataAnalysis", 100);
-      //pub.publish(canData);
+      //dataAnalysis::CanData canData;
+      //canData.set_id(pMsgBuff->ID);
+      //canData.set_data(reinterpret_cast<const char*>(pMsgBuff->DATA));
+      std_msgs::String ros_msg;
+      std::stringstream ss;
+      ss << "Id: " << pMsgBuff->ID << ", Data: " << pMsgBuff->DATA;
+      ros_msg.data = ss.str();
+      ros::Publisher canData_pub = node_handle_->advertise<std_msgs::String>(robot::common::CanDataAnalysis, 200);
+      canData_pub.publish(ros_msg);
     }
 
     return ROBOT_SUCCESS;

+ 126 - 0
src/canbus/candatatype.h

@@ -2004,6 +2004,132 @@ typedef struct
     unsigned int uiVehSpd;
 }T_RTK_SPEED;
 
+
+
+/************OBD实际油门踏板行程*******/
+typedef struct
+{
+    unsigned int : 32;
+    unsigned int : 16;
+    unsigned int obdAccPsng : 8;		//实际油门踏板行程
+    unsigned int : 8;
+}T_OBD_1A1;
+
+//实际油门踏板行程
+typedef struct
+{
+    unsigned int obdAccPsng;			//实际油门踏板行程
+}T_OBD_ACC_PSNG;
+
+#define OBD_ACC_PSNG_RATIO		255	//实际油门踏板行程比例
+
+/************OBD实际制动踏板行程*******/
+typedef struct
+{
+    unsigned int : 8;
+    unsigned int obdBrkPsng : 8;		//实际制动踏板行程
+    unsigned int : 16;
+    unsigned int : 32;
+}T_OBD_0F1;
+
+//实际制动踏板行程
+typedef struct
+{
+    unsigned int obdBrkPsng;			//实际制动踏板行程
+}T_OBD_BRK_PSNG;
+
+#define OBD_BRK_PSNG_RATIO		255	//实际制动踏板行程比例
+
+/************OBD实际挡位*******/
+typedef struct
+{
+    unsigned int obdSftPsng : 8;		//实际挡位
+    unsigned int : 24;
+    unsigned int : 32;
+}T_OBD_135;
+
+//实际挡位
+typedef struct
+{
+    unsigned int obdSftPsng;			//实际挡位
+}T_OBD_SFT_PSNG;
+
+#define SFT_BETWEEN_RANGE		0	//Between Range
+#define SFT_PARK_RANGE		    1	//Park Range
+#define SFT_REVERSE_RANGE		2	//Reverse Range
+#define SFT_NEUTRAL_RANGE		3	//Neutral Range
+#define SFT_DRIVE_RANGE	    	4	//Drive Range
+
+/************OBD车辆手刹状态*******/
+typedef struct
+{
+    unsigned int : 32;
+    unsigned int obdVehHBrkStatFix: 4;    //车辆手刹状态固定位
+    unsigned int obdVehHBrkStat : 4;	 	//车辆手刹状态
+    unsigned int : 24;
+}T_OBD_1F1;
+
+//车辆手刹状态
+typedef struct
+{
+    unsigned int obdVehHBrkStatFix;    //车辆手刹状态固定位
+    unsigned int obdVehHBrkStat;			//车辆手刹状态
+
+}T_OBD_VEH_BRK_STAT;
+
+/************OBD实际车辆启动状态*******/
+typedef struct
+{
+    unsigned int obdVehSwStat : 8;		//实际车辆启动状态
+    unsigned int : 24;
+    unsigned int : 32;
+}T_OBD_121;
+
+//实际车辆启动状态
+typedef struct
+{
+    unsigned int obdVehSwStat;			//实际车辆启动状态
+}T_OBD_VEH_SW_STAT;
+
+#define VEH_LOCK     0  //LOCK熄火
+#define VEH_ACC      1  //ACC部分上电
+#define VEH_ON       2  //ON已启动
+#define VEH_START    3  //START打火
+
+/************OBD实际方向盘转角*******/
+typedef struct
+{
+    unsigned int : 8;
+    int obdStrAng : 16;		//实际方向盘转角
+    unsigned int : 8;
+    unsigned int : 32;
+}T_OBD_1E5;
+
+//实际方向盘转角
+typedef struct
+{
+    int obdStrAng;			//实际方向盘转角
+}T_OBD_STR_ANG;
+
+#define OBD_STR_ANG_RATIO		16	//实际方向盘转角比例
+
+/************OBD实际发动机转速*******/
+typedef struct
+{
+    unsigned int : 8;
+    unsigned int obdEngSpd : 16;		//实际发动机转速
+    unsigned int : 8;
+    unsigned int : 32;
+}T_OBD_0C9;
+
+//实际发动机转速
+typedef struct
+{
+    unsigned int obdEngSpd;			//实际发动机转速
+}T_OBD_ENG_SPD;
+
+#define OBD_ENG_SPD_RATIO		16	//实际发动机转速比例
+
 } // namespace canbus
 
 } // namespace robot

+ 150 - 0
src/canbus/messagecoder.cpp

@@ -598,7 +598,122 @@ void MessageCoder::CanMsgAnalyseErr(unsigned char * ucData, T_MOT_CTR_ERR * tMot
     tMotCtrErr->uiErrz = tCtrErrCode.z;
 }
 
+//OBD实际油门踏板行程--数据解析
+void MessageCoder::OBDAnalyseID_1A1(unsigned char *ucData, T_OBD_ACC_PSNG *tOBDAccPsng)
+{
+    T_OBD_1A1 tOBD1A1 = { 0 };
+    unsigned char ucCanMsgSrc[8] = { 0 };
+
+    memcpy(ucCanMsgSrc, ucData, 8);
+    memcpy(&tOBD1A1, ucCanMsgSrc, 8);
+
+    tOBDAccPsng->obdAccPsng = tOBD1A1.obdAccPsng / OBD_ACC_PSNG_RATIO;
+}
+
+//OBD实际制动踏板行程--数据解析
+void MessageCoder::OBDAnalyseID_0F1(unsigned char *ucData, T_OBD_BRK_PSNG *tOBDBrkPsng)
+{
+    T_OBD_0F1 tOBD0F1 = { 0 };
+    unsigned char ucCanMsgSrc[8] = { 0 };
+
+    memcpy(ucCanMsgSrc, ucData, 8);
+    memcpy(&tOBD0F1, ucCanMsgSrc, 8);
+
+    tOBDBrkPsng->obdBrkPsng = tOBD0F1.obdBrkPsng / OBD_BRK_PSNG_RATIO;
+}
+
+//OBD实际挡位--数据解析
+void MessageCoder::OBDAnalyseID_135(unsigned char *ucData, T_OBD_SFT_PSNG *tOBDSftPsng)
+{
+    T_OBD_135 tOBD135 = { 0 };
+    unsigned char ucCanMsgSrc[8] = { 0 };
+
+    memcpy(ucCanMsgSrc, ucData, 8);
+    memcpy(&tOBD135, ucCanMsgSrc, 8);
+
+    switch(tOBD135.obdSftPsng)
+    {
+    case 0:
+        tOBDSftPsng->obdSftPsng = SFT_PARK_RANGE;   //P
+        break;
+    case 3:
+        tOBDSftPsng->obdSftPsng = SFT_REVERSE_RANGE;   //R
+        break;
+    case 1:
+        tOBDSftPsng->obdSftPsng = SFT_NEUTRAL_RANGE;  //N
+        break;
+    case 2:
+        tOBDSftPsng->obdSftPsng = SFT_DRIVE_RANGE;  //D
+        break;
+    default:
+        tOBDSftPsng->obdSftPsng = SFT_BETWEEN_RANGE;
+        break;
+    }
+}
+
+//OBD车辆手刹状态--数据解析
+void MessageCoder::OBDAnalyseID_1F1(unsigned char *ucData, T_OBD_VEH_BRK_STAT *tOBDVehBrkStat)
+{
+    T_OBD_1F1 tOBD1F1 = { 0 };
+    unsigned char ucCanMsgSrc[8] = { 0 };
+
+    memcpy(ucCanMsgSrc, ucData, 8);
+    memcpy(&tOBD1F1, ucCanMsgSrc, 8);
+
+    tOBDVehBrkStat->obdVehHBrkStat = tOBD1F1.obdVehHBrkStat;
+}
 
+//OBD实际车辆启动状态--数据解析
+void MessageCoder::OBDAnalyseID_121(unsigned char *ucData, T_OBD_VEH_SW_STAT *tOBDVehSwStat)
+{
+    T_OBD_121 tOBD121 = { 0 };
+    unsigned char ucCanMsgSrc[8] = { 0 };
+
+    memcpy(ucCanMsgSrc, ucData, 8);
+    memcpy(&tOBD121, ucCanMsgSrc, 8);
+
+    switch (tOBD121.obdVehSwStat) {
+    case 4:
+        tOBDVehSwStat->obdVehSwStat = VEH_LOCK;   //Lock
+        break;
+    case 5:
+        tOBDVehSwStat->obdVehSwStat = VEH_ACC;    //Acc
+        break;
+    case 7:
+        tOBDVehSwStat->obdVehSwStat = VEH_START;     //Start
+        break;
+    case 6:
+        tOBDVehSwStat->obdVehSwStat = VEH_ON;    //ON
+        break;
+    default:
+        break;
+    }
+
+}
+
+//OBD实际方向盘转角--数据解析
+void MessageCoder::OBDAnalyseID_1E5(unsigned char *ucData, T_OBD_STR_ANG *tOBDStrAng)
+{
+    T_OBD_1E5 tOBD1E5 = { 0 };
+    unsigned char ucCanMsgSrc[8] = { 0 };
+
+    memcpy(ucCanMsgSrc, ucData, 8);
+    memcpy(&tOBD1E5, ucCanMsgSrc, 8);
+
+    tOBDStrAng->obdStrAng = tOBD1E5.obdStrAng / OBD_STR_ANG_RATIO;
+}
+
+//OBD实际发动机转速--数据解析
+void MessageCoder::OBDAnalyseID_0C9(unsigned char *ucData, T_OBD_ENG_SPD *tOBDEngSpd)
+{
+    T_OBD_0C9 tOBD0C9 = { 0 };
+    unsigned char ucCanMsgSrc[8] = { 0 };
+
+    memcpy(ucCanMsgSrc, ucData, 8);
+    memcpy(&tOBD0C9, ucCanMsgSrc, 8);
+
+    tOBDEngSpd->obdEngSpd = tOBD0C9.obdEngSpd / OBD_ENG_SPD_RATIO;
+}
 
 //控制器上电命令--数据组包
 void MessageCoder::CanMsgPackageID_5F1(T_POWER_ON_REQUEST * tPowOnReq, TPCANMsg *tCanMsg)
@@ -1156,6 +1271,41 @@ void * MessageCoder::CanMsgAnalyse(int id,unsigned char * ucData)
         CanMsgAnalyseErr(ucData, &tMotCtrErrStr);
         p = &tMotCtrErrStr;
         break;
+    case 0x1A1://OBD实际油门踏板行程
+        T_OBD_ACC_PSNG tOBDAccPsng;
+        OBDAnalyseID_1A1(ucData,&tOBDAccPsng);
+        p = &tOBDAccPsng;
+        break;
+    case 0x0F1://OBD实际制动踏板行程
+        T_OBD_BRK_PSNG tOBDBrkPsng;
+        OBDAnalyseID_0F1(ucData,&tOBDBrkPsng);
+        p = &tOBDBrkPsng;
+        break;
+    case 0x135://OBD实际挡位
+        T_OBD_SFT_PSNG tOBDSftPsng;
+        OBDAnalyseID_135(ucData,&tOBDSftPsng);
+        p = &tOBDSftPsng;
+        break;
+    case 0x1F1://OBD车辆手刹状态
+        T_OBD_VEH_BRK_STAT tOBDVehBrkStat;
+        OBDAnalyseID_1F1(ucData,&tOBDVehBrkStat);
+        p = &tOBDVehBrkStat;
+        break;
+    case 0x121://OBD实际车辆启动状态
+        T_OBD_VEH_SW_STAT tOBDVehSwStat;
+        OBDAnalyseID_121(ucData,&tOBDVehSwStat);
+        p = &tOBDVehSwStat;
+        break;
+    case 0x1E5://OBD实际方向盘转角
+        T_OBD_STR_ANG tOBDStrAng;
+        OBDAnalyseID_1E5(ucData,&tOBDStrAng);
+        p = &tOBDStrAng;
+        break;
+    case 0x0C9://OBD实际发动机转速
+        T_OBD_ENG_SPD tOBDEngSpd;
+        OBDAnalyseID_0C9(ucData,&tOBDEngSpd);
+        p = &tOBDEngSpd;
+        break;
     default:
         break;
     }

+ 21 - 0
src/canbus/messagecoder.h

@@ -93,6 +93,27 @@ private:
     //油门(acc)、制动(brk)、挡位(sft)X、挡位(sft)Y、转向(str)电机报警--数据解析
     static void CanMsgAnalyseErr(unsigned char *ucData, T_MOT_CTR_ERR *tMotCtrErr);
 
+    //OBD实际油门踏板行程--数据解析
+    static void OBDAnalyseID_1A1(unsigned char *ucData, T_OBD_ACC_PSNG *tOBDAccPsng);
+
+    //OBD实际制动踏板行程--数据解析
+    static void OBDAnalyseID_0F1(unsigned char *ucData, T_OBD_BRK_PSNG *tOBDBrkPsng);
+
+    //OBD实际挡位--数据解析
+    static void OBDAnalyseID_135(unsigned char *ucData, T_OBD_SFT_PSNG *tOBDSftPsng);
+
+    //OBD车辆手刹状态--数据解析
+    static void OBDAnalyseID_1F1(unsigned char *ucData, T_OBD_VEH_BRK_STAT *tOBDVehBrkStat);
+
+    //OBD实际车辆启动状态--数据解析
+    static void OBDAnalyseID_121(unsigned char *ucData, T_OBD_VEH_SW_STAT *tOBDVehSwStat);
+
+    //OBD实际方向盘转角--数据解析
+    static void OBDAnalyseID_1E5(unsigned char *ucData, T_OBD_STR_ANG *tOBDStrAng);
+
+    //OBD实际发动机转速--数据解析
+    static void OBDAnalyseID_0C9(unsigned char *ucData, T_OBD_ENG_SPD *tOBDEngSpd);
+
     //控制器上电命令--数据组包
     static void CanMsgPackageID_5F1(T_POWER_ON_REQUEST *tPowOnReq, TPCANMsg *tCanMsg);
 

+ 0 - 102
src/common/messagecoder.h

@@ -1,102 +0,0 @@
-#include"../canbus/candatatype.h"
-
-#ifndef MESSAGECODER_H
-#define MESSAGECODER_H
-
-namespace robot {
-namespace common {
-
-class MessageCoder{
-
-private:
-    //字符串反转
-    static void CharReverse(unsigned char *s, int n);
-
-    //执行机构使能请求--数据解析
-    static void CanMsgAnalyseID_5F2(unsigned char * ucData, canbus::T_ACTUATOR_ENABLE_REQUEST *tActEnableReq);
-
-    //转向执行机构控制命令--数据解析
-    static void CanMsgAnalyseID_5F5(unsigned char *ucData, canbus::T_STR_ACT_CTR_REQ *tStrActCtrReq);
-
-    //车辆状态1--数据解析
-    static void CanMsgAnalyseID_6F1(unsigned char *ucData, canbus::T_VEHICLE_STATUS_1 *tVehicleStat1);
-
-    //车辆状态2--数据解析
-    static void CanMsgAnalyseID_6F2(unsigned char *ucData, canbus::T_VEHICLE_STATUS_2 *tVehicleStat2);
-
-    //车辆状态3--数据解析
-    static void CanMsgAnalyseID_6F3(unsigned char *ucData, canbus::T_VEHICLE_STATUS_3 *tVehicleStat3);
-
-    //工控机状态--数据解析
-    static void CanMsgAnalyseID_6F4(unsigned char *ucData, canbus::T_COMPUTER_STATUS *tComputerStat);
-
-    //机器人执行机构实际位置--数据解析
-    static void CanMsgAnalyseID_6E0(unsigned char *ucData, canbus::T_RBT_ACT_PSNG *tRbtActPsng);
-
-    //踏板学习位置反馈--数据解析
-    static void CanMsgAnalyseID_6E1(unsigned char *ucData, canbus::T_ACC_BRK_PSNG *tAccBrkPsng);
-
-    //转向学习位置反馈--数据解析
-    static void CanMsgAnalyseID_6E2(unsigned char *ucData, canbus::T_STR_LRN_PSNG *tStrLrnPsng);
-
-    //档位学习位置反馈1--数据解析
-    static void CanMsgAnalyseID_6E3(unsigned char *ucData, canbus::T_SFT_LRN_PST_1 *tSftLrnPst1);
-
-    //控制器上电状态--数据解析
-    static void CanMsgAnalyseID_6E4(unsigned char *ucData, canbus::T_CTR_POW_STATUS *tCtrPowStatus);
-
-    //执行机构使能状态--数据解析
-    static void CanMsgAnalyseID_6E5(unsigned char *ucData, canbus::T_ACT_ENABLE_STATUS *tActEnableStatus);
-
-    //油门控制状态反馈--数据解析
-    static void CanMsgAnalyseID_6E6(unsigned char *ucData, canbus::T_ACC_CTR_STATUS *tAccCtrStatus);
-
-    //制动踏板控制状态反馈--数据解析
-    static void CanMsgAnalyseID_6E7(unsigned char *ucData, canbus::T_BRK_CTR_STATUS *tBrkCtrStatus);
-
-    //离合踏板控制状态反馈--数据解析
-    static void CanMsgAnalyseID_6E8(unsigned char *ucData, canbus::T_CLCH_CTR_STATUS *tClchCtrStatus);
-
-    //转向控制状态反馈--数据解析
-    static void CanMsgAnalyseID_6E9(unsigned char *ucData, canbus::T_STR_STATUS *tStrStatus);
-
-    //档位控制状态反馈--数据解析
-    static void CanMsgAnalyseID_6EA(unsigned char *ucData, canbus::T_SFT_STATUS *tSftStatus);
-
-    //系统运行状态参数反馈1--数据解析
-    static void CanMsgAnalyseID_6EB(unsigned char *ucData, canbus::T_SYS_INFO_1 *tSysInfo1);
-
-    //系统运行状态参数反馈2--数据解析
-    static void CanMsgAnalyseID_6ED(unsigned char *ucData, canbus::T_SYS_INFO_2 *tSysInfo2);
-
-    //系统学习状态反馈--数据解析
-    static void CanMsgAnalyseID_6EE(unsigned char *ucData, canbus::T_SYS_LRN *tSysLrn);
-
-    //档位学习位置反馈2--数据解析
-    static void CanMsgAnalyseID_6EF(unsigned char *ucData, canbus::T_SFT_LRN_PST_2 *tSFtLrnPst2);
-
-    //系统监控状态反馈--数据解析
-    static void CanMsgAnalyseID_6D0(unsigned char *ucData, canbus::T_SYS_MONITOR *tSysMonitor);
-
-    //系统报警--数据解析
-    static void CanMsgAnalyseID_6D1(unsigned char *ucData, canbus::T_SYS_ERR *tSysErr);
-
-    //方向盘位置时间控制请求--数据解析
-    static void CanMsgAnalyseID_6D7(unsigned char *ucData, canbus::T_STEER_PST_TIME_REQ *tSteerPstTimeReq);
-
-    //Estop系统信息--数据解析
-    static void CanMsgAnalyseID_2E0(unsigned char *ucData, canbus::T_ESTOP_INFO *tEstopInfo);
-
-    //Estop故障码--数据解析
-    static void CanMsgAnalyseID_2E1(unsigned char *ucData, canbus::T_ESTOP_ERR *tEstopErr);
-
-public:
-    //数据解析
-    static void * CanMsgAnalyse(int id, unsigned char * ucData);
-};
-
-}// namespace common
-
-}// namespace robot
-
-#endif // MESSAGECODER_H

+ 2 - 0
src/common/messagetopics.h

@@ -20,6 +20,8 @@ namespace common{
 
 const std::string Geometry = "geometry";
 
+const std::string CanDataAnalysis = "canDataAnalysis";
+
 } // common
 
 } // robot

+ 1 - 1
src/localization/localization.cpp

@@ -8,7 +8,7 @@
 #include "localization.h"
 #include "coordsconvertion.h"
 #include <geometry_msgs/Point.h>
-#include "../common/messagechannels.h"
+#include "../common/messagetopics.h"
 
 
 

+ 0 - 387
src/protobuf/CanData.pb.cc

@@ -1,387 +0,0 @@
-// Generated by the protocol buffer compiler.  DO NOT EDIT!
-// source: CanData.proto
-
-#define INTERNAL_SUPPRESS_PROTOBUF_FIELD_DEPRECATION
-#include "CanData.pb.h"
-
-#include <algorithm>
-
-#include <google/protobuf/stubs/common.h>
-#include <google/protobuf/stubs/once.h>
-#include <google/protobuf/io/coded_stream.h>
-#include <google/protobuf/wire_format_lite_inl.h>
-#include <google/protobuf/descriptor.h>
-#include <google/protobuf/generated_message_reflection.h>
-#include <google/protobuf/reflection_ops.h>
-#include <google/protobuf/wire_format.h>
-// @@protoc_insertion_point(includes)
-
-namespace dataAnalysis {
-
-namespace {
-
-const ::google::protobuf::Descriptor* CanData_descriptor_ = NULL;
-const ::google::protobuf::internal::GeneratedMessageReflection*
-  CanData_reflection_ = NULL;
-
-}  // namespace
-
-
-void protobuf_AssignDesc_CanData_2eproto() {
-  protobuf_AddDesc_CanData_2eproto();
-  const ::google::protobuf::FileDescriptor* file =
-    ::google::protobuf::DescriptorPool::generated_pool()->FindFileByName(
-      "CanData.proto");
-  GOOGLE_CHECK(file != NULL);
-  CanData_descriptor_ = file->message_type(0);
-  static const int CanData_offsets_[2] = {
-    GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(CanData, id_),
-    GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(CanData, data_),
-  };
-  CanData_reflection_ =
-    new ::google::protobuf::internal::GeneratedMessageReflection(
-      CanData_descriptor_,
-      CanData::default_instance_,
-      CanData_offsets_,
-      GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(CanData, _has_bits_[0]),
-      GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(CanData, _unknown_fields_),
-      -1,
-      ::google::protobuf::DescriptorPool::generated_pool(),
-      ::google::protobuf::MessageFactory::generated_factory(),
-      sizeof(CanData));
-}
-
-namespace {
-
-GOOGLE_PROTOBUF_DECLARE_ONCE(protobuf_AssignDescriptors_once_);
-inline void protobuf_AssignDescriptorsOnce() {
-  ::google::protobuf::GoogleOnceInit(&protobuf_AssignDescriptors_once_,
-                 &protobuf_AssignDesc_CanData_2eproto);
-}
-
-void protobuf_RegisterTypes(const ::std::string&) {
-  protobuf_AssignDescriptorsOnce();
-  ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
-    CanData_descriptor_, &CanData::default_instance());
-}
-
-}  // namespace
-
-void protobuf_ShutdownFile_CanData_2eproto() {
-  delete CanData::default_instance_;
-  delete CanData_reflection_;
-}
-
-void protobuf_AddDesc_CanData_2eproto() {
-  static bool already_here = false;
-  if (already_here) return;
-  already_here = true;
-  GOOGLE_PROTOBUF_VERIFY_VERSION;
-
-  ::google::protobuf::DescriptorPool::InternalAddGeneratedFile(
-    "\n\rCanData.proto\022\014dataAnalysis\"#\n\007CanData"
-    "\022\n\n\002id\030\001 \002(\r\022\014\n\004data\030\002 \002(\t", 66);
-  ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile(
-    "CanData.proto", &protobuf_RegisterTypes);
-  CanData::default_instance_ = new CanData();
-  CanData::default_instance_->InitAsDefaultInstance();
-  ::google::protobuf::internal::OnShutdown(&protobuf_ShutdownFile_CanData_2eproto);
-}
-
-// Force AddDescriptors() to be called at static initialization time.
-struct StaticDescriptorInitializer_CanData_2eproto {
-  StaticDescriptorInitializer_CanData_2eproto() {
-    protobuf_AddDesc_CanData_2eproto();
-  }
-} static_descriptor_initializer_CanData_2eproto_;
-
-// ===================================================================
-
-#ifndef _MSC_VER
-const int CanData::kIdFieldNumber;
-const int CanData::kDataFieldNumber;
-#endif  // !_MSC_VER
-
-CanData::CanData()
-  : ::google::protobuf::Message() {
-  SharedCtor();
-  // @@protoc_insertion_point(constructor:dataAnalysis.CanData)
-}
-
-void CanData::InitAsDefaultInstance() {
-}
-
-CanData::CanData(const CanData& from)
-  : ::google::protobuf::Message() {
-  SharedCtor();
-  MergeFrom(from);
-  // @@protoc_insertion_point(copy_constructor:dataAnalysis.CanData)
-}
-
-void CanData::SharedCtor() {
-  ::google::protobuf::internal::GetEmptyString();
-  _cached_size_ = 0;
-  id_ = 0u;
-  data_ = const_cast< ::std::string*>(&::google::protobuf::internal::GetEmptyStringAlreadyInited());
-  ::memset(_has_bits_, 0, sizeof(_has_bits_));
-}
-
-CanData::~CanData() {
-  // @@protoc_insertion_point(destructor:dataAnalysis.CanData)
-  SharedDtor();
-}
-
-void CanData::SharedDtor() {
-  if (data_ != &::google::protobuf::internal::GetEmptyStringAlreadyInited()) {
-    delete data_;
-  }
-  if (this != default_instance_) {
-  }
-}
-
-void CanData::SetCachedSize(int size) const {
-  GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
-  _cached_size_ = size;
-  GOOGLE_SAFE_CONCURRENT_WRITES_END();
-}
-const ::google::protobuf::Descriptor* CanData::descriptor() {
-  protobuf_AssignDescriptorsOnce();
-  return CanData_descriptor_;
-}
-
-const CanData& CanData::default_instance() {
-  if (default_instance_ == NULL) protobuf_AddDesc_CanData_2eproto();
-  return *default_instance_;
-}
-
-CanData* CanData::default_instance_ = NULL;
-
-CanData* CanData::New() const {
-  return new CanData;
-}
-
-void CanData::Clear() {
-  if (_has_bits_[0 / 32] & 3) {
-    id_ = 0u;
-    if (has_data()) {
-      if (data_ != &::google::protobuf::internal::GetEmptyStringAlreadyInited()) {
-        data_->clear();
-      }
-    }
-  }
-  ::memset(_has_bits_, 0, sizeof(_has_bits_));
-  mutable_unknown_fields()->Clear();
-}
-
-bool CanData::MergePartialFromCodedStream(
-    ::google::protobuf::io::CodedInputStream* input) {
-#define DO_(EXPRESSION) if (!(EXPRESSION)) goto failure
-  ::google::protobuf::uint32 tag;
-  // @@protoc_insertion_point(parse_start:dataAnalysis.CanData)
-  for (;;) {
-    ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoff(127);
-    tag = p.first;
-    if (!p.second) goto handle_unusual;
-    switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
-      // required uint32 id = 1;
-      case 1: {
-        if (tag == 8) {
-          DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
-                   ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>(
-                 input, &id_)));
-          set_has_id();
-        } else {
-          goto handle_unusual;
-        }
-        if (input->ExpectTag(18)) goto parse_data;
-        break;
-      }
-
-      // required string data = 2;
-      case 2: {
-        if (tag == 18) {
-         parse_data:
-          DO_(::google::protobuf::internal::WireFormatLite::ReadString(
-                input, this->mutable_data()));
-          ::google::protobuf::internal::WireFormat::VerifyUTF8StringNamedField(
-            this->data().data(), this->data().length(),
-            ::google::protobuf::internal::WireFormat::PARSE,
-            "data");
-        } else {
-          goto handle_unusual;
-        }
-        if (input->ExpectAtEnd()) goto success;
-        break;
-      }
-
-      default: {
-      handle_unusual:
-        if (tag == 0 ||
-            ::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
-            ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
-          goto success;
-        }
-        DO_(::google::protobuf::internal::WireFormat::SkipField(
-              input, tag, mutable_unknown_fields()));
-        break;
-      }
-    }
-  }
-success:
-  // @@protoc_insertion_point(parse_success:dataAnalysis.CanData)
-  return true;
-failure:
-  // @@protoc_insertion_point(parse_failure:dataAnalysis.CanData)
-  return false;
-#undef DO_
-}
-
-void CanData::SerializeWithCachedSizes(
-    ::google::protobuf::io::CodedOutputStream* output) const {
-  // @@protoc_insertion_point(serialize_start:dataAnalysis.CanData)
-  // required uint32 id = 1;
-  if (has_id()) {
-    ::google::protobuf::internal::WireFormatLite::WriteUInt32(1, this->id(), output);
-  }
-
-  // required string data = 2;
-  if (has_data()) {
-    ::google::protobuf::internal::WireFormat::VerifyUTF8StringNamedField(
-      this->data().data(), this->data().length(),
-      ::google::protobuf::internal::WireFormat::SERIALIZE,
-      "data");
-    ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased(
-      2, this->data(), output);
-  }
-
-  if (!unknown_fields().empty()) {
-    ::google::protobuf::internal::WireFormat::SerializeUnknownFields(
-        unknown_fields(), output);
-  }
-  // @@protoc_insertion_point(serialize_end:dataAnalysis.CanData)
-}
-
-::google::protobuf::uint8* CanData::SerializeWithCachedSizesToArray(
-    ::google::protobuf::uint8* target) const {
-  // @@protoc_insertion_point(serialize_to_array_start:dataAnalysis.CanData)
-  // required uint32 id = 1;
-  if (has_id()) {
-    target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(1, this->id(), target);
-  }
-
-  // required string data = 2;
-  if (has_data()) {
-    ::google::protobuf::internal::WireFormat::VerifyUTF8StringNamedField(
-      this->data().data(), this->data().length(),
-      ::google::protobuf::internal::WireFormat::SERIALIZE,
-      "data");
-    target =
-      ::google::protobuf::internal::WireFormatLite::WriteStringToArray(
-        2, this->data(), target);
-  }
-
-  if (!unknown_fields().empty()) {
-    target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
-        unknown_fields(), target);
-  }
-  // @@protoc_insertion_point(serialize_to_array_end:dataAnalysis.CanData)
-  return target;
-}
-
-int CanData::ByteSize() const {
-  int total_size = 0;
-
-  if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
-    // required uint32 id = 1;
-    if (has_id()) {
-      total_size += 1 +
-        ::google::protobuf::internal::WireFormatLite::UInt32Size(
-          this->id());
-    }
-
-    // required string data = 2;
-    if (has_data()) {
-      total_size += 1 +
-        ::google::protobuf::internal::WireFormatLite::StringSize(
-          this->data());
-    }
-
-  }
-  if (!unknown_fields().empty()) {
-    total_size +=
-      ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
-        unknown_fields());
-  }
-  GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
-  _cached_size_ = total_size;
-  GOOGLE_SAFE_CONCURRENT_WRITES_END();
-  return total_size;
-}
-
-void CanData::MergeFrom(const ::google::protobuf::Message& from) {
-  GOOGLE_CHECK_NE(&from, this);
-  const CanData* source =
-    ::google::protobuf::internal::dynamic_cast_if_available<const CanData*>(
-      &from);
-  if (source == NULL) {
-    ::google::protobuf::internal::ReflectionOps::Merge(from, this);
-  } else {
-    MergeFrom(*source);
-  }
-}
-
-void CanData::MergeFrom(const CanData& from) {
-  GOOGLE_CHECK_NE(&from, this);
-  if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
-    if (from.has_id()) {
-      set_id(from.id());
-    }
-    if (from.has_data()) {
-      set_data(from.data());
-    }
-  }
-  mutable_unknown_fields()->MergeFrom(from.unknown_fields());
-}
-
-void CanData::CopyFrom(const ::google::protobuf::Message& from) {
-  if (&from == this) return;
-  Clear();
-  MergeFrom(from);
-}
-
-void CanData::CopyFrom(const CanData& from) {
-  if (&from == this) return;
-  Clear();
-  MergeFrom(from);
-}
-
-bool CanData::IsInitialized() const {
-  if ((_has_bits_[0] & 0x00000003) != 0x00000003) return false;
-
-  return true;
-}
-
-void CanData::Swap(CanData* other) {
-  if (other != this) {
-    std::swap(id_, other->id_);
-    std::swap(data_, other->data_);
-    std::swap(_has_bits_[0], other->_has_bits_[0]);
-    _unknown_fields_.Swap(&other->_unknown_fields_);
-    std::swap(_cached_size_, other->_cached_size_);
-  }
-}
-
-::google::protobuf::Metadata CanData::GetMetadata() const {
-  protobuf_AssignDescriptorsOnce();
-  ::google::protobuf::Metadata metadata;
-  metadata.descriptor = CanData_descriptor_;
-  metadata.reflection = CanData_reflection_;
-  return metadata;
-}
-
-
-// @@protoc_insertion_point(namespace_scope)
-
-}  // namespace dataAnalysis
-
-// @@protoc_insertion_point(global_scope)

+ 0 - 255
src/protobuf/CanData.pb.h

@@ -1,255 +0,0 @@
-// Generated by the protocol buffer compiler.  DO NOT EDIT!
-// source: CanData.proto
-
-#ifndef PROTOBUF_CanData_2eproto__INCLUDED
-#define PROTOBUF_CanData_2eproto__INCLUDED
-
-#include <string>
-
-#include <google/protobuf/stubs/common.h>
-
-#if GOOGLE_PROTOBUF_VERSION < 2006000
-#error This file was generated by a newer version of protoc which is
-#error incompatible with your Protocol Buffer headers.  Please update
-#error your headers.
-#endif
-#if 2006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION
-#error This file was generated by an older version of protoc which is
-#error incompatible with your Protocol Buffer headers.  Please
-#error regenerate this file with a newer version of protoc.
-#endif
-
-#include <google/protobuf/generated_message_util.h>
-#include <google/protobuf/message.h>
-#include <google/protobuf/repeated_field.h>
-#include <google/protobuf/extension_set.h>
-#include <google/protobuf/unknown_field_set.h>
-// @@protoc_insertion_point(includes)
-
-namespace dataAnalysis {
-
-// Internal implementation detail -- do not call these.
-void  protobuf_AddDesc_CanData_2eproto();
-void protobuf_AssignDesc_CanData_2eproto();
-void protobuf_ShutdownFile_CanData_2eproto();
-
-class CanData;
-
-// ===================================================================
-
-class CanData : public ::google::protobuf::Message {
- public:
-  CanData();
-  virtual ~CanData();
-
-  CanData(const CanData& from);
-
-  inline CanData& operator=(const CanData& from) {
-    CopyFrom(from);
-    return *this;
-  }
-
-  inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
-    return _unknown_fields_;
-  }
-
-  inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
-    return &_unknown_fields_;
-  }
-
-  static const ::google::protobuf::Descriptor* descriptor();
-  static const CanData& default_instance();
-
-  void Swap(CanData* other);
-
-  // implements Message ----------------------------------------------
-
-  CanData* New() const;
-  void CopyFrom(const ::google::protobuf::Message& from);
-  void MergeFrom(const ::google::protobuf::Message& from);
-  void CopyFrom(const CanData& from);
-  void MergeFrom(const CanData& from);
-  void Clear();
-  bool IsInitialized() const;
-
-  int ByteSize() const;
-  bool MergePartialFromCodedStream(
-      ::google::protobuf::io::CodedInputStream* input);
-  void SerializeWithCachedSizes(
-      ::google::protobuf::io::CodedOutputStream* output) const;
-  ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
-  int GetCachedSize() const { return _cached_size_; }
-  private:
-  void SharedCtor();
-  void SharedDtor();
-  void SetCachedSize(int size) const;
-  public:
-  ::google::protobuf::Metadata GetMetadata() const;
-
-  // nested types ----------------------------------------------------
-
-  // accessors -------------------------------------------------------
-
-  // required uint32 id = 1;
-  inline bool has_id() const;
-  inline void clear_id();
-  static const int kIdFieldNumber = 1;
-  inline ::google::protobuf::uint32 id() const;
-  inline void set_id(::google::protobuf::uint32 value);
-
-  // required string data = 2;
-  inline bool has_data() const;
-  inline void clear_data();
-  static const int kDataFieldNumber = 2;
-  inline const ::std::string& data() const;
-  inline void set_data(const ::std::string& value);
-  inline void set_data(const char* value);
-  inline void set_data(const char* value, size_t size);
-  inline ::std::string* mutable_data();
-  inline ::std::string* release_data();
-  inline void set_allocated_data(::std::string* data);
-
-  // @@protoc_insertion_point(class_scope:dataAnalysis.CanData)
- private:
-  inline void set_has_id();
-  inline void clear_has_id();
-  inline void set_has_data();
-  inline void clear_has_data();
-
-  ::google::protobuf::UnknownFieldSet _unknown_fields_;
-
-  ::google::protobuf::uint32 _has_bits_[1];
-  mutable int _cached_size_;
-  ::std::string* data_;
-  ::google::protobuf::uint32 id_;
-  friend void  protobuf_AddDesc_CanData_2eproto();
-  friend void protobuf_AssignDesc_CanData_2eproto();
-  friend void protobuf_ShutdownFile_CanData_2eproto();
-
-  void InitAsDefaultInstance();
-  static CanData* default_instance_;
-};
-// ===================================================================
-
-
-// ===================================================================
-
-// CanData
-
-// required uint32 id = 1;
-inline bool CanData::has_id() const {
-  return (_has_bits_[0] & 0x00000001u) != 0;
-}
-inline void CanData::set_has_id() {
-  _has_bits_[0] |= 0x00000001u;
-}
-inline void CanData::clear_has_id() {
-  _has_bits_[0] &= ~0x00000001u;
-}
-inline void CanData::clear_id() {
-  id_ = 0u;
-  clear_has_id();
-}
-inline ::google::protobuf::uint32 CanData::id() const {
-  // @@protoc_insertion_point(field_get:dataAnalysis.CanData.id)
-  return id_;
-}
-inline void CanData::set_id(::google::protobuf::uint32 value) {
-  set_has_id();
-  id_ = value;
-  // @@protoc_insertion_point(field_set:dataAnalysis.CanData.id)
-}
-
-// required string data = 2;
-inline bool CanData::has_data() const {
-  return (_has_bits_[0] & 0x00000002u) != 0;
-}
-inline void CanData::set_has_data() {
-  _has_bits_[0] |= 0x00000002u;
-}
-inline void CanData::clear_has_data() {
-  _has_bits_[0] &= ~0x00000002u;
-}
-inline void CanData::clear_data() {
-  if (data_ != &::google::protobuf::internal::GetEmptyStringAlreadyInited()) {
-    data_->clear();
-  }
-  clear_has_data();
-}
-inline const ::std::string& CanData::data() const {
-  // @@protoc_insertion_point(field_get:dataAnalysis.CanData.data)
-  return *data_;
-}
-inline void CanData::set_data(const ::std::string& value) {
-  set_has_data();
-  if (data_ == &::google::protobuf::internal::GetEmptyStringAlreadyInited()) {
-    data_ = new ::std::string;
-  }
-  data_->assign(value);
-  // @@protoc_insertion_point(field_set:dataAnalysis.CanData.data)
-}
-inline void CanData::set_data(const char* value) {
-  set_has_data();
-  if (data_ == &::google::protobuf::internal::GetEmptyStringAlreadyInited()) {
-    data_ = new ::std::string;
-  }
-  data_->assign(value);
-  // @@protoc_insertion_point(field_set_char:dataAnalysis.CanData.data)
-}
-inline void CanData::set_data(const char* value, size_t size) {
-  set_has_data();
-  if (data_ == &::google::protobuf::internal::GetEmptyStringAlreadyInited()) {
-    data_ = new ::std::string;
-  }
-  data_->assign(reinterpret_cast<const char*>(value), size);
-  // @@protoc_insertion_point(field_set_pointer:dataAnalysis.CanData.data)
-}
-inline ::std::string* CanData::mutable_data() {
-  set_has_data();
-  if (data_ == &::google::protobuf::internal::GetEmptyStringAlreadyInited()) {
-    data_ = new ::std::string;
-  }
-  // @@protoc_insertion_point(field_mutable:dataAnalysis.CanData.data)
-  return data_;
-}
-inline ::std::string* CanData::release_data() {
-  clear_has_data();
-  if (data_ == &::google::protobuf::internal::GetEmptyStringAlreadyInited()) {
-    return NULL;
-  } else {
-    ::std::string* temp = data_;
-    data_ = const_cast< ::std::string*>(&::google::protobuf::internal::GetEmptyStringAlreadyInited());
-    return temp;
-  }
-}
-inline void CanData::set_allocated_data(::std::string* data) {
-  if (data_ != &::google::protobuf::internal::GetEmptyStringAlreadyInited()) {
-    delete data_;
-  }
-  if (data) {
-    set_has_data();
-    data_ = data;
-  } else {
-    clear_has_data();
-    data_ = const_cast< ::std::string*>(&::google::protobuf::internal::GetEmptyStringAlreadyInited());
-  }
-  // @@protoc_insertion_point(field_set_allocated:dataAnalysis.CanData.data)
-}
-
-
-// @@protoc_insertion_point(namespace_scope)
-
-}  // namespace dataAnalysis
-
-#ifndef SWIG
-namespace google {
-namespace protobuf {
-
-
-}  // namespace google
-}  // namespace protobuf
-#endif  // SWIG
-
-// @@protoc_insertion_point(global_scope)
-
-#endif  // PROTOBUF_CanData_2eproto__INCLUDED

+ 0 - 8
src/protobuf/CanData.proto

@@ -1,8 +0,0 @@
-syntax = "proto2";
-package dataAnalysis;
-
-message CanData {
-  required uint32 id = 1;
-  required string data = 2;
-}
-