Преглед на файлове

修改RCU数据解析代码和数据组包代码,接收与发送需要字符串翻转

gemingyu преди 4 години
родител
ревизия
1afe1f8550
променени са 3 файла, в които са добавени 71 реда и са изтрити 23 реда
  1. 21 3
      src/canbus/canbus.cpp
  2. 1 1
      src/canbus/canbus.h
  3. 49 19
      src/canbus/messagecoder.cpp

+ 21 - 3
src/canbus/canbus.cpp

@@ -100,8 +100,8 @@ void Canbus::OnTimer(const ros::TimerEvent &) {
   {
       heatbeat = 0;
   }
-  heatbeat ++;
-  icuMonitor.uiICUAlive = heatbeat;
+  icuMonitor.uiICUAlive = heatbeat++;
+//  heatbeat ++;
   MessageCoder::CanMsgPackage((void*)&icuMonitor,robot::common::ICUMonitor,&canIcuMonitor);
   MessageCoder::CanMsgPackage((void*)&status1,robot::common::VehicleStatus1,&canStatus1);
   MessageCoder::CanMsgPackage((void*)&status2,robot::common::VehicleStatus2,&canStatus2);
@@ -110,6 +110,15 @@ void Canbus::OnTimer(const ros::TimerEvent &) {
   write_data(&canStatus2);
   write_data(&canStatus3);
   write_data(&canIcuMonitor);
+
+//  T_STR_ACT_CTR_REQ strAct = {0};
+//  strAct.iStrAngCtrReq =  2324;
+//  strAct.iStrSpdCtrReq= 10000;
+//  strAct.iStrTrqCtrReq = 5000;
+//  strAct.uiStrCtrMdReq = 1;
+//  TPCANMsg pStr;
+//    MessageCoder::CanMsgPackage((void*)&strAct,robot::common::SteerActCtrReq,&pStr);
+//  write_data(&pStr);
 }
 
 void Canbus::Stop() {
@@ -221,7 +230,16 @@ void Canbus::publish_data(TPCANMsg *pMsgBuff)
 
     char strId[4] = {0};
     sprintf(strId,"%3xh",pMsgBuff->ID);
-    LOG(INFO)<<Name()<<" Publish CanData :" << "ID:" << strId << "Data:"<<rosMsg.data;
+    char strData[16]={0};
+    MessageCoder::ConvertUnCharToStr(strData,pMsgBuff->DATA,8);
+    LOG(INFO)<<Name()<<" Publish CanData :" << "ID:" << strId << ",Data:"<<strData;
+    LOG(INFO)<<Name()<<" Msg CanData :" << "ID:" << rosMsg.id << ",Data:"<<rosMsg.data;
+
+//    T_SYS_INFO_2 info2 = *((T_SYS_INFO_2*)MessageCoder::CanMsgAnalyse(robot::common::RSysInfoBack2,pMsgBuff->DATA));
+
+//    char heart[2] = {0};
+//    sprintf(heart,"%2x",info2.uiRCUAlive);
+//    LOG(INFO)<<Name()<<" RCU Alive :" << heart;
 }
 
 int Canbus::write_data(TPCANMsg *pMsgBuff)

+ 1 - 1
src/canbus/canbus.h

@@ -125,7 +125,7 @@ class Canbus : public robot::common::RobotApp{
 
   const double duration = 0.01;
 
-  const double rate = 0.005;  //s
+  const double rate = 0.001;  //s
   //GLOBALS
   void *libm_handle = NULL;//define pointer used for file acess of libpcan.so
   HANDLE pcan_handle =NULL;//void *pcan_handle

+ 49 - 19
src/canbus/messagecoder.cpp

@@ -36,6 +36,7 @@ void MessageCoder::CanMsgAnalyseID_5F2(unsigned char * ucData, T_ACTUATOR_ENABLE
     T_CONTROL_CMD_5F2 tCtrCmd5F2 = { 0 };
     unsigned char ucCanMsgSrc[8] = { 0 };
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tCtrCmd5F2, ucCanMsgSrc, CAN_MSG_LEN);
     tActEnableReq->uiAccClchCtrReq = tCtrCmd5F2.uiAccClchCtrReq;
     tActEnableReq->uiAccMotEnReq = tCtrCmd5F2.uiAccMotEnReq;
@@ -58,6 +59,7 @@ void MessageCoder::CanMsgAnalyseID_5F5(unsigned char * ucData, T_STR_ACT_CTR_REQ
 
     unsigned char ucCanMsgSrc[8] = { 0 };
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tCtrCmd5F5, ucCanMsgSrc, CAN_MSG_LEN);
 
     memset(&tCtrCmd5F5Union, 0, sizeof(T_CONTROL_CMD_5F5_UNION));
@@ -77,6 +79,7 @@ void MessageCoder::CanMsgAnalyseID_6F1(unsigned char * ucData, T_VEHICLE_STATUS_
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tStatIn6F1, ucCanMsgSrc, CAN_MSG_LEN);
 
     tVehicleStat1->uiAccPsng = tStatIn6F1.uiAccPsng;
@@ -97,6 +100,7 @@ void MessageCoder::CanMsgAnalyseID_6F2(unsigned char * ucData, T_VEHICLE_STATUS_
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tStatIn6F2, ucCanMsgSrc, CAN_MSG_LEN);
 
     memset(&tStatIn6F2Union, 0, sizeof(T_STATE_IN_6F2_UNION));
@@ -116,6 +120,7 @@ void MessageCoder::CanMsgAnalyseID_6F3(unsigned char * ucData, T_VEHICLE_STATUS_
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tStatIn6F3, ucCanMsgSrc, CAN_MSG_LEN);
 
     tVehicleStat3->uiVehBatQut = tStatIn6F3.uiVehBatQut;
@@ -130,6 +135,7 @@ void MessageCoder::CanMsgAnalyseID_6F4(unsigned char * ucData, T_COMPUTER_STATUS
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tStatIn6F4, ucCanMsgSrc, CAN_MSG_LEN);
 
     tComputerStat->uiCmpStat = tStatIn6F4.uiCmpStat;
@@ -142,6 +148,7 @@ void MessageCoder::CanMsgAnalyseID_6E0(unsigned char * ucData, T_RBT_ACT_PSNG *
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tStatout6E0, ucCanMsgSrc, CAN_MSG_LEN);
 
     T_STATE_OUT_6E0_UNION tStateOut6E0Union;
@@ -162,6 +169,7 @@ void MessageCoder::CanMsgAnalyseID_6E1(unsigned char * ucData, T_ACC_BRK_PSNG *
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tStatout6E1, ucCanMsgSrc, CAN_MSG_LEN);
 
     tAccBrkPsng->uiClbtAccPsng0 = tStatout6E1.uiClbtAccPsng0;
@@ -177,6 +185,7 @@ void MessageCoder::CanMsgAnalyseID_6E2(unsigned char * ucData, T_STR_LRN_PSNG *
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tStatout6E2, ucCanMsgSrc, CAN_MSG_LEN);
 
     T_STATE_OUT_6E2_UNION tStateOut6E2Union;
@@ -196,6 +205,7 @@ void MessageCoder::CanMsgAnalyseID_6E3(unsigned char * ucData, T_SFT_LRN_PST_1 *
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tStatout6E3, ucCanMsgSrc, CAN_MSG_LEN);
 
     T_STATE_OUT_6E3_UNION tStateOut6E3Union;
@@ -219,6 +229,7 @@ void MessageCoder::CanMsgAnalyseID_6E4(unsigned char * ucData, T_CTR_POW_STATUS
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tStatout6E4, ucCanMsgSrc, CAN_MSG_LEN);
 
     tCtrPowStatus->uiAccCtrPowStat = tStatout6E4.uiAccCtrPowStat;
@@ -237,6 +248,7 @@ void MessageCoder::CanMsgAnalyseID_6E5(unsigned char * ucData, T_ACT_ENABLE_STAT
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tStatout6E5, ucCanMsgSrc, CAN_MSG_LEN);
 
     tActEnableStatus->uiAccClchCtrStat = tStatout6E5.uiAccClchCtrStat;
@@ -257,6 +269,7 @@ void MessageCoder::CanMsgAnalyseID_6E6(unsigned char * ucData, T_ACC_CTR_STATUS
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tStatout6E6, ucCanMsgSrc, CAN_MSG_LEN);
 
     tAccCtrStatus->iAccDspSpd = tStatout6E6.iAccDspSpd;
@@ -271,6 +284,7 @@ void MessageCoder::CanMsgAnalyseID_6E7(unsigned char * ucData, T_BRK_CTR_STATUS
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tStatout6E7, ucCanMsgSrc, CAN_MSG_LEN);
 
     tBrkCtrStatus->iBrkDspSpd = tStatout6E7.iBrkDspSpd;
@@ -288,6 +302,7 @@ void MessageCoder::CanMsgAnalyseID_6E8(unsigned char * ucData, T_CLCH_CTR_STATUS
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tStatout6E8, ucCanMsgSrc, CAN_MSG_LEN);
 
     T_STATE_OUT_6E8_UNION tStateOut6E8Union;
@@ -308,6 +323,7 @@ void MessageCoder::CanMsgAnalyseID_6E9(unsigned char * ucData, T_STR_STATUS * tS
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tStatout6E9, ucCanMsgSrc, CAN_MSG_LEN);
 
     T_STATE_OUT_6E9_UNION tStateOut6E9Union;
@@ -329,6 +345,7 @@ void MessageCoder::CanMsgAnalyseID_6EA(unsigned char * ucData, T_SFT_STATUS * tS
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tStatout6EA, ucCanMsgSrc, CAN_MSG_LEN);
 
     T_STATE_OUT_6EA_UNION tStateOut6EAUnion;
@@ -354,6 +371,7 @@ void MessageCoder::CanMsgAnalyseID_6EB(unsigned char * ucData, T_SYS_INFO_1 * tS
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tStatout6EB, ucCanMsgSrc, CAN_MSG_LEN);
 
     tSysInfo1->uiAccMotCur = tStatout6EB.uiAccMotCur;
@@ -372,6 +390,7 @@ void MessageCoder::CanMsgAnalyseID_6ED(unsigned char * ucData, T_SYS_INFO_2 * tS
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tStatout6ED, ucCanMsgSrc, CAN_MSG_LEN);
 
     tSysInfo2->uiAccCtrAlive = tStatout6ED.uiAccCtrAlive;
@@ -398,6 +417,7 @@ void MessageCoder::CanMsgAnalyseID_6EE(unsigned char * ucData, T_SYS_LRN * tSysL
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tStatout6EE, ucCanMsgSrc, CAN_MSG_LEN);
 
     tSysLrn->uiAcc0LrnStat = tStatout6EE.uiAcc0LrnStat;
@@ -422,6 +442,7 @@ void MessageCoder::CanMsgAnalyseID_6EF(unsigned char * ucData, T_SFT_LRN_PST_2 *
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tStatout6EF, ucCanMsgSrc, CAN_MSG_LEN);
 
     T_STATE_OUT_6EF_UNION tStateOut6EFUnion;
@@ -445,6 +466,7 @@ void MessageCoder::CanMsgAnalyseID_6D0(unsigned char * ucData, T_SYS_MONITOR * t
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tStatout6D0, ucCanMsgSrc, CAN_MSG_LEN);
 
     tSysMonitor->iCtrTmp = tStatout6D0.iCtrTmp;
@@ -475,6 +497,7 @@ void MessageCoder::CanMsgAnalyseID_6D1(unsigned char * ucData, T_SYS_ERR * tSysE
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tStatOut6D1, ucCanMsgSrc, CAN_MSG_LEN);
 
     tSysErr->uiSysErra = tStatOut6D1.uiSysErra;
@@ -512,6 +535,7 @@ void MessageCoder::CanMsgAnalyseID_6D7(unsigned char * ucData, T_STEER_PST_TIME_
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tCtrCmd6D7, ucCanMsgSrc, CAN_MSG_LEN);
 
     tSteerPstTimeReq->uiNumReq = tCtrCmd6D7.uiNumReq;
@@ -525,6 +549,7 @@ void MessageCoder::CanMsgAnalyseID_2E0(unsigned char * ucData, T_ESTOP_INFO * tE
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tEstop2E0, ucCanMsgSrc, CAN_MSG_LEN);
 
     tEstopInfo->uiEstpAbnStat = tEstop2E0.uiEstpAbnStat;
@@ -540,6 +565,7 @@ void MessageCoder::CanMsgAnalyseID_2E1(unsigned char * ucData, T_ESTOP_ERR * tEs
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tEstop2E1, ucCanMsgSrc, CAN_MSG_LEN);
 
     tEstopErr->uiEspErra = tEstop2E1.uiEspErra;
@@ -561,6 +587,7 @@ void MessageCoder::CanMsgAnalyseErr(unsigned char * ucData, T_MOT_CTR_ERR * tMot
     unsigned char ucCanMsgSrc[8] = { 0 };
 
     memcpy(ucCanMsgSrc, ucData, CAN_MSG_LEN);
+    CharReverse(ucCanMsgSrc,8);
     memcpy(&tCtrErrCode, ucCanMsgSrc, CAN_MSG_LEN);
 
     tMotCtrErr->uiErra = tCtrErrCode.a;
@@ -738,6 +765,7 @@ void MessageCoder::CanMsgPackageID_5F1(T_POWER_ON_REQUEST * tPowOnReq, TPCANMsg
     tCtrCmd5F1.uiYSftArmCtrPowReq = tPowOnReq->uiYSftArmCtrPowReq;
 
     memcpy(ucCanMsgSrc,&tCtrCmd5F1,CAN_MSG_LEN);
+        CharReverse(ucCanMsgSrc,8);
     memcpy(tCanMsg->DATA, ucCanMsgSrc, CAN_MSG_LEN);
     tCanMsg->ID = robot::common::PowerOnReq;
     tCanMsg->LEN = 8;
@@ -763,7 +791,7 @@ void MessageCoder::CanMsgPackageID_5F2(T_ACTUATOR_ENABLE_REQUEST *tActEnableReq,
     tCtrCmd5F2.uiYSftMotEnReq = tActEnableReq->uiYSftMotEnReq;
 
     memcpy(ucCanMsgSrc, &tCtrCmd5F2, CAN_MSG_LEN);
-
+    CharReverse(ucCanMsgSrc,8);
     memcpy(tCanMsg->DATA, ucCanMsgSrc, CAN_MSG_LEN);
     tCanMsg->ID = robot::common::ActuatorEnableReq;
     tCanMsg->LEN = 8;
@@ -788,7 +816,7 @@ void MessageCoder::CanMsgPackageID_5F3(T_LEARN_MODE_REQUEST * tLearnMdReq, TPCAN
     tCtrCmd5F3.uiSysLrnReq = tLearnMdReq->uiSysLrnReq;
 
     memcpy(ucCanMsgSrc, &tCtrCmd5F3, CAN_MSG_LEN);
-
+    CharReverse(ucCanMsgSrc,8);
     memcpy(tCanMsg->DATA, ucCanMsgSrc, CAN_MSG_LEN);
     tCanMsg->ID = robot::common::LearnModeReq;
     tCanMsg->LEN = 8;
@@ -814,6 +842,7 @@ void MessageCoder::CanMsgPackageID_5F4(T_PEDAL_ACT_CTR_REQ * tPedalActCtrReq, TP
     tCtrCmd5F4.uiBrkPsngCtrReqL = tCtrCmd5F4Union.tCtrCmd5F4Src.uiBrkPsngCtrReqL;
 
     memcpy(ucCanMsgSrc, &tCtrCmd5F4, CAN_MSG_LEN);
+        CharReverse(ucCanMsgSrc,8);
     memcpy(tCanMsg->DATA, ucCanMsgSrc, CAN_MSG_LEN);
     tCanMsg->ID = robot::common::PedalActCtrReq;
     tCanMsg->LEN = 8;
@@ -836,7 +865,7 @@ void MessageCoder::CanMsgPackageID_5F5(T_STR_ACT_CTR_REQ * tStrActCtrReq, TPCANM
     tCtrCmd5F5.iStrTrqCtrReq = tStrActCtrReq->iStrTrqCtrReq;
     tCtrCmd5F5.uiStrCtrMdReq = tStrActCtrReq->uiStrCtrMdReq;
     memcpy(ucCanMsgSrc, &tCtrCmd5F5, CAN_MSG_LEN);
-
+    CharReverse(ucCanMsgSrc,8);
     memcpy(tCanMsg->DATA, ucCanMsgSrc, CAN_MSG_LEN);
     tCanMsg->ID = robot::common::SteerActCtrReq;
     tCanMsg->LEN = 8;
@@ -855,7 +884,7 @@ void MessageCoder::CanMsgPackageID_5F6(T_SFT_ACT_CTR_REQ * tSftActCtrReq, TPCANM
     tCtrCmd5F6.uiSftPsngCtrReq = tSftActCtrReq->uiSftPsngCtrReq;
 
     memcpy(ucCanMsgSrc, &tCtrCmd5F6, CAN_MSG_LEN);
-
+    CharReverse(ucCanMsgSrc,8);
     memcpy(tCanMsg->DATA, ucCanMsgSrc, CAN_MSG_LEN);
     tCanMsg->ID = robot::common::ShiftActCtrReq;
     tCanMsg->LEN = 8;
@@ -871,7 +900,7 @@ void MessageCoder::CanMsgPackageID_5F7(T_RBT_SLF_CHK_CTR_REQ * tRbtSlfChkCtrRq,
     tCtrCmd5F7.uiRbtSlfChkReq = tRbtSlfChkCtrRq->uiRbtSlfChkReq;
 
     memcpy(ucCanMsgSrc, &tCtrCmd5F7, CAN_MSG_LEN);
-
+    CharReverse(ucCanMsgSrc,8);
     memcpy(tCanMsg->DATA, ucCanMsgSrc, CAN_MSG_LEN);
     tCanMsg->ID = robot::common::RobotSelfCheckCtrReq;
     tCanMsg->LEN = 8;
@@ -893,7 +922,7 @@ void MessageCoder::CanMsgPackageID_5F8(T_RBT_DRIVER_CTR * tRbtDriverCtr, TPCANMs
     tCtrCmd5F8.uiYSftMotCtrl = tRbtDriverCtr->uiYSftMotCtrl;
 
     memcpy(ucCanMsgSrc, &tCtrCmd5F8, CAN_MSG_LEN);
-
+    CharReverse(ucCanMsgSrc,8);
     memcpy(tCanMsg->DATA, ucCanMsgSrc, CAN_MSG_LEN);
     tCanMsg->ID = robot::common::RobotDriverCtr;
     tCanMsg->LEN = 8;
@@ -915,7 +944,7 @@ void MessageCoder::CanMsgPackageID_5F9(T_RBT_MANAGER * tRbtManager, TPCANMsg *tC
     tCtrCmd5F9.uiYSftMotInt = tRbtManager->uiYSftMotInt;
 
     memcpy(ucCanMsgSrc, &tCtrCmd5F9, CAN_MSG_LEN);
-
+    CharReverse(ucCanMsgSrc,8);
     memcpy(tCanMsg->DATA, ucCanMsgSrc, CAN_MSG_LEN);
     tCanMsg->ID = robot::common::RobotManager;
     tCanMsg->LEN = 8;
@@ -932,7 +961,7 @@ void MessageCoder::CanMsgPackageID_5FA(T_ICU_MONITOR * tIcuMonitor, TPCANMsg *tC
     tCtrCmd5FA.uiICUClsReq = tIcuMonitor->uiICUClsReq;
 
     memcpy(ucCanMsgSrc, &tCtrCmd5FA, CAN_MSG_LEN);
-
+    CharReverse(ucCanMsgSrc,8);
     memcpy(tCanMsg->DATA, ucCanMsgSrc, CAN_MSG_LEN);
     tCanMsg->ID = robot::common::ICUMonitor;
     tCanMsg->LEN = 8;
@@ -950,7 +979,7 @@ void MessageCoder::CanMsgPackageID_5FB(T_ACT_ACC_CTR_REQ * tActAccCtrReq, TPCANM
     tCtrCmd5FB.uiStrAccCtrReq = tActAccCtrReq->uiStrAccCtrReq;
 
     memcpy(ucCanMsgSrc, &tCtrCmd5FB, CAN_MSG_LEN);
-
+    CharReverse(ucCanMsgSrc,8);
     memcpy(tCanMsg->DATA, ucCanMsgSrc, CAN_MSG_LEN);
     tCanMsg->ID = robot::common::ActuatorAccelerateCtrReq;
     tCanMsg->LEN = 8;
@@ -969,7 +998,7 @@ void MessageCoder::CanMsgPackageID_5FC(T_ACT_CTR_LIMT * tActCtrLimt, TPCANMsg *t
     tCtrCmd5FC.uiSftType = tActCtrLimt->uiSftType;
 
     memcpy(ucCanMsgSrc, &tCtrCmd5FC, CAN_MSG_LEN);
-
+    CharReverse(ucCanMsgSrc,8);
     memcpy(tCanMsg->DATA, ucCanMsgSrc, CAN_MSG_LEN);
     tCanMsg->ID = robot::common::ActuatorCtrLimit;
     tCanMsg->LEN = 8;
@@ -987,7 +1016,7 @@ void MessageCoder::CanMsgPackageID_5FD(T_TRQ_PRTCT_STP * tTrqPrtctSetp, TPCANMsg
     tCtrCmd5FD.uiStrTorqSwitch = tTrqPrtctSetp->uiStrTorqSwitch;
 
     memcpy(ucCanMsgSrc, &tCtrCmd5FD, CAN_MSG_LEN);
-
+    CharReverse(ucCanMsgSrc,8);
     memcpy(tCanMsg->DATA, ucCanMsgSrc, CAN_MSG_LEN);
     tCanMsg->ID = robot::common::TorqueProtectStp;
     tCanMsg->LEN = 8;
@@ -1005,7 +1034,7 @@ void MessageCoder::CanMsgPackageID_5FE(T_BRK_FRC_CTR_STP * tBrkFrcCtrStp, TPCANM
     tCtrCmd5FE.uiFrcSpd = tBrkFrcCtrStp->uiFrcSpd;
 
     memcpy(ucCanMsgSrc, &tCtrCmd5FE, CAN_MSG_LEN);
-
+    CharReverse(ucCanMsgSrc,8);
     memcpy(tCanMsg->DATA, ucCanMsgSrc, CAN_MSG_LEN);
     tCanMsg->ID = robot::common::BrakeForceCtrStp;
     tCanMsg->LEN = 8;
@@ -1031,7 +1060,7 @@ void MessageCoder::CanMsgPackageID_7F3(T_STR_TRNGL_LN_CTR * tStrTrnglLnCtr, TPCA
     tCtrCmd7F3.uiStrTT = tStrTrnglLnCtr->uiStrTT;
 
     memcpy(ucCanMsgSrc, &tCtrCmd7F3, CAN_MSG_LEN);
-
+    CharReverse(ucCanMsgSrc,8);
     memcpy(tCanMsg->DATA, ucCanMsgSrc, CAN_MSG_LEN);
     tCanMsg->ID = robot::common::SteerTranLineCtr;
     tCanMsg->LEN = 8;
@@ -1052,7 +1081,7 @@ void MessageCoder::CanMsgPackageID_7F4(T_STR_SIN_CTR * tStrSinCtr, TPCANMsg *tCa
     tCtrCmd7F4.uiStrFrtk = tStrSinCtr->uiStrFrtk;
 
     memcpy(ucCanMsgSrc, &tCtrCmd7F4, CAN_MSG_LEN);
-
+    CharReverse(ucCanMsgSrc,8);
     memcpy(tCanMsg->DATA, ucCanMsgSrc, CAN_MSG_LEN);
     tCanMsg->ID = robot::common::SteerSinCtr;
     tCanMsg->LEN = 8;
@@ -1070,7 +1099,7 @@ void MessageCoder::CanMsgPackageID_7F5(T_ACC_PSTN_CTR_STP * tAccPstnCtrStp, TPCA
     tCtrCmd7F5.uiBrkTm = tAccPstnCtrStp->uiBrkTm;
 
     memcpy(ucCanMsgSrc, &tCtrCmd7F5, CAN_MSG_LEN);
-
+    CharReverse(ucCanMsgSrc,8);
     memcpy(tCanMsg->DATA, ucCanMsgSrc, CAN_MSG_LEN);
     tCanMsg->ID = robot::common::AccPositionCtrStp;
     tCanMsg->LEN = 8;
@@ -1095,7 +1124,7 @@ void MessageCoder::CanMsgPackageID_7F6(T_STR_PSTN_TM_CTR * tStrPstnTmCtr, TPCANM
     tCtrCmd7F6.uiTotalNum = tStrPstnTmCtr->uiTotalNum;
 
     memcpy(ucCanMsgSrc, &tCtrCmd7F6, CAN_MSG_LEN);
-
+    CharReverse(ucCanMsgSrc,8);
     memcpy(tCanMsg->DATA, ucCanMsgSrc, CAN_MSG_LEN);
     tCanMsg->ID = robot::common::SteerPositionTimeCtr;
     tCanMsg->LEN = 8;
@@ -1111,7 +1140,7 @@ void MessageCoder::CanMsgPackageID_7F7(T_VEHICLE_START * tVehicleStart, TPCANMsg
     tCtrCmd7F7.uiVehSwReq = tVehicleStart->uiVehSwReq;
 
     memcpy(ucCanMsgSrc, &tCtrCmd7F7, CAN_MSG_LEN);
-
+    CharReverse(ucCanMsgSrc,8);
     memcpy(tCanMsg->DATA, ucCanMsgSrc, CAN_MSG_LEN);
     tCanMsg->ID = robot::common::VehicleStart;
     tCanMsg->LEN = 8;
@@ -1135,7 +1164,7 @@ void MessageCoder::CanMsgPackageID_6F1(T_VEHICLE_STATUS_1 *tVehicleStatus1, TPCA
     tStateIn6F1.uiVehSwStat = tVehicleStatus1->uiVehSwStat;
 
     memcpy(ucCanMsgSrc, &tStateIn6F1, CAN_MSG_LEN);
-
+    CharReverse(ucCanMsgSrc,8);
     memcpy(tCanMsg->DATA, ucCanMsgSrc, CAN_MSG_LEN);
     tCanMsg->ID = robot::common::VehicleStatus1;
     tCanMsg->LEN = 8;
@@ -1159,6 +1188,7 @@ void MessageCoder::CanMsgPackageID_6F2(T_VEHICLE_STATUS_2 *tVehicleStatus2, TPCA
     tStateIn6F2.uiVehSpd = tVehicleStatus2->uiVehSpd;
 
     memcpy(ucCanMsgSrc, &tStateIn6F2, CAN_MSG_LEN);
+        CharReverse(ucCanMsgSrc,8);
     memcpy(tCanMsg->DATA, ucCanMsgSrc, CAN_MSG_LEN);
     tCanMsg->ID = robot::common::VehicleStatus2;
     tCanMsg->LEN = 8;
@@ -1176,7 +1206,7 @@ void MessageCoder::CanMsgPackageID_6F3(T_VEHICLE_STATUS_3 *tVehicleStatus3, TPCA
     tStateIn6F3.uiVehBatVlt = tVehicleStatus3->uiVehBatVlt;
 
     memcpy(ucCanMsgSrc, &tStateIn6F3, CAN_MSG_LEN);
-
+    CharReverse(ucCanMsgSrc,8);
     memcpy(tCanMsg->DATA, ucCanMsgSrc, CAN_MSG_LEN);
     tCanMsg->ID = robot::common::VehicleStatus3;
     tCanMsg->LEN = 8;