Browse Source

fix(driver_ARS408):reduce cpu consume. feat(driver_ultrasonic_dauxi_KS136A):add an ultrasonic driver

孙嘉城 3 years ago
parent
commit
246ec773cd
22 changed files with 1980 additions and 42 deletions
  1. 1 1
      src/driver/driver_can_nvidia_agx_new/main.cpp
  2. 1 1
      src/driver/driver_radar_continental_ARS408_SRR308/cansend_producer.cpp
  3. 2 2
      src/driver/driver_radar_continental_ARS408_SRR308/decode_cfg.cpp
  4. 2 2
      src/driver/driver_radar_continental_ARS408_SRR308/decode_cfg.h
  5. 2 6
      src/driver/driver_radar_continental_ARS408_SRR308/driver_radar_continental_ARS408_SRR308.pro
  6. 2 0
      src/driver/driver_radar_continental_ARS408_SRR308/iv_msgunit.h
  7. 2 2
      src/driver/driver_radar_continental_ARS408_SRR308/main.cpp
  8. 107 0
      src/driver/driver_ultrasonic_dauxi_KS136A/can_producer_consumer.cpp
  9. 35 0
      src/driver/driver_ultrasonic_dauxi_KS136A/can_producer_consumer.h
  10. 1255 0
      src/driver/driver_ultrasonic_dauxi_KS136A/canrecv_consumer.cpp
  11. 85 0
      src/driver/driver_ultrasonic_dauxi_KS136A/canrecv_consumer.h
  12. 71 0
      src/driver/driver_ultrasonic_dauxi_KS136A/cansend_consumer.cpp
  13. 29 0
      src/driver/driver_ultrasonic_dauxi_KS136A/cansend_consumer.h
  14. 70 0
      src/driver/driver_ultrasonic_dauxi_KS136A/cansend_producer.cpp
  15. 36 0
      src/driver/driver_ultrasonic_dauxi_KS136A/cansend_producer.h
  16. 17 0
      src/driver/driver_ultrasonic_dauxi_KS136A/decode_cfg.cpp
  17. 19 0
      src/driver/driver_ultrasonic_dauxi_KS136A/decode_cfg.h
  18. 57 0
      src/driver/driver_ultrasonic_dauxi_KS136A/driver_ultrasonic_dauxi_KS136A.pro
  19. 8 0
      src/driver/driver_ultrasonic_dauxi_KS136A/driver_ultrasonic_dauxi_KS136A.xml
  20. 21 0
      src/driver/driver_ultrasonic_dauxi_KS136A/iv_msgunit.h
  21. 129 0
      src/driver/driver_ultrasonic_dauxi_KS136A/main.cpp
  22. 29 28
      src/include/proto/ultrasonic.proto

+ 1 - 1
src/driver/driver_can_nvidia_agx_new/main.cpp

@@ -139,7 +139,7 @@ int main(int argc, char *argv[])
     std::string strmemsend1 = xp.GetParam("cansend1_agx","cansend1");
     std::string strmemrecv1 = xp.GetParam("canrecv1_agx","canrecv1");
     std::string strcanname0 = xp.GetParam("canname0","can0");
-    std::string strcanname1 = xp.GetParam("canname0","can1");
+    std::string strcanname1 = xp.GetParam("canname1","can1");
 
     gpcanctrl = new canctrl(strmemsend0.data(),strmemrecv0.data(),strmemsend1.data(),strmemrecv1.data(),strcanname0.data(),strcanname1.data());
     gpcanctrl->start();

+ 1 - 1
src/driver/driver_radar_continental_ARS408_SRR308/cansend_producer.cpp

@@ -215,7 +215,7 @@ void CANSend_Producer::run()
         }
         else
         {
-            std::this_thread::sleep_for(std::chrono::microseconds(100));//sleep 0.1ms
+            std::this_thread::sleep_for(std::chrono::microseconds(1000));//sleep 1ms
         }
     }
 }

+ 2 - 2
src/driver/driver_radar_continental_ARS408_SRR308/decode_cfg.cpp

@@ -1,6 +1,6 @@
 #include "decode_cfg.h"
 
-int decode_setup_cfg_from_xml(setupConfig_t &setupConfig , std::string xmlFilePath)
+int DecodeSetupCfgFromXML(setupConfig_t &setupConfig , std::string xmlFilePath)
 {
     iv::xmlparam::Xmlparam xp(xmlFilePath);
 
@@ -49,7 +49,7 @@ int decode_setup_cfg_from_xml(setupConfig_t &setupConfig , std::string xmlFilePa
     return 0;
 }
 
-int decode_radar_cfg_from_yaml(RadarConfiguration_ch0_t &radarConfiguration , const std::string &yamlFilePath)
+int DecodeRadarCfgFromYAML(RadarConfiguration_ch0_t &radarConfiguration , const std::string &yamlFilePath)
 {
     YAML::Node config;
     try

+ 2 - 2
src/driver/driver_radar_continental_ARS408_SRR308/decode_cfg.h

@@ -39,7 +39,7 @@ struct setupConfig_t
     std::string collDetRegionCfgYAML_Path = "CollDetRegion_Cfg.yaml";
 };
 
-int decode_setup_cfg_from_xml(setupConfig_t &setupConfig , std::string xmlFilePath);
-int decode_radar_cfg_from_yaml(RadarConfiguration_ch0_t &radarConfiguration , const std::string &yamlFilePath);
+int DecodeSetupCfgFromXML(setupConfig_t &setupConfig , std::string xmlFilePath);
+int DecodeRadarCfgFromYAML(RadarConfiguration_ch0_t &radarConfiguration , const std::string &yamlFilePath);
 
 #endif // DECODE_CFG_H

+ 2 - 6
src/driver/driver_radar_continental_ARS408_SRR308/driver_radar_continental_ARS408_SRR308.pro

@@ -4,22 +4,19 @@ QT += xml dbus
 CONFIG += c++11 console
 CONFIG -= app_bundle
 
-
-QMAKE_LFLAGS += -no-pie
-
 # The following define makes your compiler emit warnings if you use
 # any feature of Qt which as been marked deprecated (the exact warnings
 # depend on your compiler). Please consult the documentation of the
 # deprecated API in order to know how to port your code away from it.
 DEFINES += QT_DEPRECATED_WARNINGS
 
-QMAKE_LFLAGS += -no-pie
-
 # You can also make your code fail to compile if you use deprecated APIs.
 # In order to do so, uncomment the following line.
 # You can also select to disable deprecated APIs only up to a certain version of Qt.
 #DEFINES += QT_DISABLE_DEPRECATED_BEFORE=0x060000    # disables all the APIs deprecated before Qt 6.0.0
 
+QMAKE_LFLAGS += -no-pie
+
 HEADERS += \
     ../../include/msgtype/radarobject.pb.h \
     ../../include/msgtype/radarobjectarray.pb.h \
@@ -121,4 +118,3 @@ else: unix:!android: target.path = /opt/$${TARGET}/bin
 !include(../../../include/ivyaml-cpp.pri ) {
     error( "Couldn't find the ivyaml-cpp.pri file!" )
 }
-

+ 2 - 0
src/driver/driver_radar_continental_ARS408_SRR308/iv_msgunit.h

@@ -1,6 +1,8 @@
 #ifndef IV_MSGUNIT_H
 #define IV_MSGUNIT_H
 
+#include <memory>
+
 namespace iv {
 struct msgunit
 {

+ 2 - 2
src/driver/driver_radar_continental_ARS408_SRR308/main.cpp

@@ -154,12 +154,12 @@ int main(int argc, char *argv[])
 //    givlog->verbose("%s", strpath.data());
 //    std::cout<<strpath.toStdString()<<std::endl;
 
-    decode_setup_cfg_from_xml(setupConfig,strpath.toStdString());
+    DecodeSetupCfgFromXML(setupConfig,strpath.toStdString());
 
     if(setupConfig.radarCfgApply!=0)
     {
         RadarConfiguration_ch0_t radarConfiguration;
-        decode_radar_cfg_from_yaml(radarConfiguration,setupConfig.radarCfgYAML_Path);
+        DecodeRadarCfgFromYAML(radarConfiguration,setupConfig.radarCfgYAML_Path);
     }
 
     strncpy(shmCANSend.mstrmsgname,setupConfig.strMemCANSend.data(),255);

+ 107 - 0
src/driver/driver_ultrasonic_dauxi_KS136A/can_producer_consumer.cpp

@@ -0,0 +1,107 @@
+#include "can_producer_consumer.h"
+
+CAN_Producer_Consumer::CAN_Producer_Consumer(const int bufSize)
+{
+    bufferSize = bufSize;
+    buffer.resize(bufferSize);
+    freeSpace.release(bufferSize);
+}
+
+uint64_t CAN_Producer_Consumer::Produce_Element(const iv::can::canraw &xraw) //return the position of first element int this storage
+{
+    uint64_t tempPtr = producerPtr % bufferSize;
+    freeSpace.acquire();
+    producerLock.lock();
+    buffer[producerPtr++ % bufferSize] = xraw;
+    producerLock.unlock();
+    usedSpace.release();
+
+    return tempPtr;
+}
+
+uint64_t CAN_Producer_Consumer::Produce_Elements(const iv::can::canmsg &xmsg,const int &size)
+{
+    uint64_t tempPtr = producerPtr % bufferSize;
+    if(size < xmsg.rawmsg_size())
+    {
+        std::cout<<"Warning! the input size is less than the number of message element."<<std::endl;
+        freeSpace.acquire(size);
+        producerLock.lock();
+        for(int i=0;i<size;i++)
+        {
+            buffer[producerPtr++ % bufferSize] = xmsg.rawmsg(i);
+        }
+        producerLock.unlock();
+        usedSpace.release(size);
+    }
+    else
+    {
+        if(size > xmsg.rawmsg_size())
+            std::cout<<"Warning! the input size is more than the number of message element."<<std::endl;
+        freeSpace.acquire(xmsg.rawmsg_size());
+        producerLock.lock();
+        for(int i=0;i<xmsg.rawmsg_size();i++)
+        {
+            buffer[producerPtr++ % bufferSize] = xmsg.rawmsg(i);
+        }
+        producerLock.unlock();
+        usedSpace.release(xmsg.rawmsg_size());
+    }
+
+    return tempPtr;
+}
+
+uint64_t CAN_Producer_Consumer::Produce_Elements_From_CANMsg(const iv::can::canmsg &xmsg)
+{
+    uint64_t tempPtr = producerPtr % bufferSize;
+    freeSpace.acquire(xmsg.rawmsg_size());
+    producerLock.lock();
+    for(int i=0;i<xmsg.rawmsg_size();i++)
+    {
+        buffer[producerPtr++ % bufferSize] = xmsg.rawmsg(i);
+    }
+    producerLock.unlock();
+    usedSpace.release(xmsg.rawmsg_size());
+
+    return tempPtr;
+}
+
+iv::can::canraw CAN_Producer_Consumer::Consume_Element()
+{
+    iv::can::canraw xraw;
+    usedSpace.acquire(); //this function is block mode
+    consumerLock.lock();
+    xraw = buffer.at(consumerPtr++ % bufferSize);
+    consumerLock.unlock();
+    freeSpace.release();
+
+    return xraw;
+}
+
+iv::can::canmsg CAN_Producer_Consumer::Consume_Elements(const int &size)
+{
+    iv::can::canmsg xmsg;
+    usedSpace.acquire(size); //this function is block mode
+    consumerLock.lock();
+    for(int i=0;i<size;i++)
+    {
+        xmsg.add_rawmsg()->CopyFrom(buffer.at(consumerPtr++ % bufferSize));
+    }
+    consumerLock.unlock();
+    freeSpace.release(size);
+
+    return xmsg;
+}
+
+uint64_t CAN_Producer_Consumer::Consume_Element_To_CANMsg(iv::can::canmsg &xmsg)
+{
+    uint64_t tempPtr = consumerPtr % bufferSize;
+    usedSpace.acquire(); //this function is block mode
+    iv::can::canraw *praw = xmsg.add_rawmsg();
+    consumerLock.lock();
+    praw->CopyFrom(buffer.at(consumerPtr++ % bufferSize));
+    consumerLock.unlock();
+    freeSpace.release();
+
+    return tempPtr;
+}

+ 35 - 0
src/driver/driver_ultrasonic_dauxi_KS136A/can_producer_consumer.h

@@ -0,0 +1,35 @@
+#ifndef CAN_PRODUCER_CONSUMER_H
+#define CAN_PRODUCER_CONSUMER_H
+
+#include <QSemaphore>
+#include <QMutex>
+#include <QVector>
+
+#include <iostream>
+
+#include "canmsg.pb.h"
+
+class CAN_Producer_Consumer
+{
+public:
+    CAN_Producer_Consumer(const int bufSize = 4096);
+    uint64_t Produce_Element(const iv::can::canraw &xraw); //return the position of first element int this storage
+    uint64_t Produce_Elements(const iv::can::canmsg &xmsg,const int &size); //return the position of first element int this storage
+    uint64_t Produce_Elements_From_CANMsg(const iv::can::canmsg &xmsg); //return the position of first element int this storage
+    iv::can::canraw Consume_Element();
+    iv::can::canmsg Consume_Elements(const int &size);
+    uint64_t Consume_Element_To_CANMsg(iv::can::canmsg &xmsg); //return the position of the consumed element
+
+    QVector<iv::can::canraw> buffer;
+
+private:
+    uint16_t bufferSize = 4096;
+    QSemaphore freeSpace;
+    QSemaphore usedSpace;
+    uint64_t producerPtr = 0;
+    QMutex producerLock;
+    uint64_t consumerPtr = 0;
+    QMutex consumerLock;
+};
+
+#endif // CAN_PRODUCER_CONSUMER_H

+ 1255 - 0
src/driver/driver_ultrasonic_dauxi_KS136A/canrecv_consumer.cpp

@@ -0,0 +1,1255 @@
+//#include "canrecv_consumer.h"
+
+//#include "math.h"
+
+//extern setupConfig_t setupConfig;
+//extern iv::msgunit shmSonar;
+
+//CANRecv_Consumer::CANRecv_Consumer(CAN_Producer_Consumer *pBuf)
+//{
+//    pBuffer = pBuf;
+
+//    QObject::connect(this,&CANRecv_Consumer::RadarObjectArray_Ready,this,&CANRecv_Consumer::RadarObjectArray_Ready_Slot);
+
+//    iv::radar::radarobject xradarObj;
+//    vradarObj.fill(xradarObj,RADAR_OBJ_MAX_NUM);
+//    radarObjFreshFlag.fill(false,RADAR_OBJ_MAX_NUM);
+//}
+
+//CANRecv_Consumer::~CANRecv_Consumer()
+//{
+//    requestInterruption();
+//    while(this->isFinished() == false);
+//}
+
+//void CANRecv_Consumer::Clear_CAN_PrivateTempVariable(void)
+//{
+//    CAN_ID = 0x000u;
+//    CAN_DLC = 0;
+//    for(int i=0;i<8;i++) CAN_data[i] = 0x00;
+//}
+
+//uint32_t CANRecv_Consumer::Trans_From_CANRaw(const iv::can::canraw &xraw) //only for standard data frame, return can id
+//{
+//    this->Clear_CAN_PrivateTempVariable();
+//    CAN_ID = xraw.id();
+//    CAN_DLC = xraw.len();
+//    char tempData[8];
+//    int tempLen = (xraw.data().size() > 8) ? 8 : xraw.data().size();
+//    strncpy(tempData,xraw.data().data(),tempLen);
+//    for(int i=0;i<tempLen;i++)
+//    {
+//        CAN_data[i] = (uint8_t)tempData[i];
+//    }
+
+//    return CAN_ID;
+//}
+
+//void CANRecv_Consumer::Pack_Info_To_SHM_ch0(uint32_t can_id)
+//{
+//    std::string major,minor,patch;
+//    iv::radar::radarobject *pobj;
+//    iv::radar::radarobject xradarObj_null;
+//    double tempDX,tempDY,tempVX,tempVY,tempAX,tempAY,tempOri;
+//    uint8_t tempObjID;
+
+//    switch (can_id) {
+//    case 0x201:
+//        persistent_Error = ars408_can_database_ch0_rx.RadarState_ch0.RadarState_Persistent_Error;
+//        interference_Error = ars408_can_database_ch0_rx.RadarState_ch0.RadarState_Interference;
+//        temperature_Error = ars408_can_database_ch0_rx.RadarState_ch0.RadarState_Temperature_Error;
+//        temporary_Error = ars408_can_database_ch0_rx.RadarState_ch0.RadarState_Temporary_Error;
+//        voltage_Error = ars408_can_database_ch0_rx.RadarState_ch0.RadarState_Voltage_Error;
+//        speed_Loss = ars408_can_database_ch0_rx.RadarState_ch0.RadarState_MotionRxState & 0x01;
+//        yaw_Rate_Loss = (ars408_can_database_ch0_rx.RadarState_ch0.RadarState_MotionRxState >> 1) & 0x01;
+//        break;
+//    case 0x700:
+//        major = std::to_string((unsigned int)ars408_can_database_ch0_rx.VersionID_ch0.Version_MajorRelease);
+//        minor = std::to_string((unsigned int)ars408_can_database_ch0_rx.VersionID_ch0.Version_MinorRelease);
+//        patch = std::to_string((unsigned int)ars408_can_database_ch0_rx.VersionID_ch0.Version_PatchLevel);
+//        radar_Version = major + "." + minor + "." + patch;
+//        break;
+//    case 0x60A:
+//        if(ars408_can_database_ch0_rx.Obj_0_Status_ch0.Obj_NofObjects == 0)
+//        {
+//            xradarObjArray.Clear();
+//            xradarObjArray.set_mstime(QDateTime::currentMSecsSinceEpoch());
+//            xradarObjArray.set_persistent_error(persistent_Error);
+//            xradarObjArray.set_interference_error(interference_Error);
+//            xradarObjArray.set_temperature_error(temperature_Error);
+//            xradarObjArray.set_temporary_error(temporary_Error);
+//            xradarObjArray.set_voltage_error(voltage_Error);
+//            xradarObjArray.set_speed_loss(speed_Loss);
+//            xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
+//            xradarObjArray.set_radar_version(radar_Version);
+
+//            radarObjArraySend_lock.lock();
+//            radarObjArray_send.CopyFrom(xradarObjArray);
+//            radarObjArraySend_lock.unlock();
+//            emit RadarObjectArray_Ready();
+//        }
+//        else
+//        {
+//            xradarObjArray.Clear();
+//            for(int i=0;i<RADAR_OBJ_MAX_NUM;i++)
+//            {
+//                if(radarObjFreshFlag[i] == true)
+//                {
+//                    pobj = xradarObjArray.add_obj();
+//                    pobj->CopyFrom(vradarObj[i]);
+//                }
+//            }
+//            xradarObjArray.set_mstime(QDateTime::currentMSecsSinceEpoch());
+//            xradarObjArray.set_persistent_error(persistent_Error);
+//            xradarObjArray.set_interference_error(interference_Error);
+//            xradarObjArray.set_temperature_error(temperature_Error);
+//            xradarObjArray.set_temporary_error(temporary_Error);
+//            xradarObjArray.set_voltage_error(voltage_Error);
+//            xradarObjArray.set_speed_loss(speed_Loss);
+//            xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
+//            xradarObjArray.set_radar_version(radar_Version);
+
+//            radarObjArraySend_lock.lock();
+//            radarObjArray_send.CopyFrom(xradarObjArray);
+//            radarObjArraySend_lock.unlock();
+////            std::cout<<radarObjArray_send.obj_size()<<std::endl;
+//            emit RadarObjectArray_Ready();
+//        }
+//        //clear the obj vector and flag vector
+//        vradarObj.fill(xradarObj_null,RADAR_OBJ_MAX_NUM);
+//        radarObjFreshFlag.fill(false,RADAR_OBJ_MAX_NUM);
+//        break;
+//    case 0x60B:
+//        tempObjID = ars408_can_database_ch0_rx.Obj_1_General_ch0.Obj_ID;
+//        radarObjFreshFlag[tempObjID] = true;
+//        tempDX = -ars408_can_database_ch0_rx.Obj_1_General_ch0.Obj_DistLat_phys;
+//        tempDY = ars408_can_database_ch0_rx.Obj_1_General_ch0.Obj_DistLong_phys;
+//        this->Rotate_Translate(tempDX,tempDY,setupConfig.radarAzimuth,setupConfig.radarOffsetX,setupConfig.radarOffsetY);
+//        vradarObj[tempObjID].set_x(tempDX);
+//        vradarObj[tempObjID].set_y(tempDY);
+//        tempVX = -ars408_can_database_ch0_rx.Obj_1_General_ch0.Obj_VrelLat_phys;
+//        tempVY = ars408_can_database_ch0_rx.Obj_1_General_ch0.Obj_VrelLong_phys;
+//        this->Rotate_Translate(tempVX,tempVY,setupConfig.radarAzimuth,setupConfig.radarOffsetX,setupConfig.radarOffsetY);
+//        vradarObj[tempObjID].set_vx(tempVX);
+//        vradarObj[tempObjID].set_vy(tempVY);
+//        vradarObj[tempObjID].set_vel(sqrt(tempVX*tempVX+tempVY*tempVY));
+//        vradarObj[tempObjID].set_bvalid(true);
+//        vradarObj[tempObjID].set_id(tempObjID);
+//        vradarObj[tempObjID].set_dynamic_property(ars408_can_database_ch0_rx.Obj_1_General_ch0.Obj_DynProp);
+//        vradarObj[tempObjID].set_rcs_radarcrosssection(ars408_can_database_ch0_rx.Obj_1_General_ch0.Obj_RCS_phys);
+//        break;
+//    case 0x60C:
+//        tempObjID = ars408_can_database_ch0_rx.Obj_2_Quality_ch0.Obj_ID;
+//        vradarObj[tempObjID].set_distlong_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch0_rx.Obj_2_Quality_ch0.Obj_DistLong_rms));
+//        vradarObj[tempObjID].set_distlat_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch0_rx.Obj_2_Quality_ch0.Obj_DistLat_rms));
+//        vradarObj[tempObjID].set_vrellong_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch0_rx.Obj_2_Quality_ch0.Obj_VrelLong_rms));
+//        vradarObj[tempObjID].set_vrellat_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch0_rx.Obj_2_Quality_ch0.Obj_VrelLat_rms));
+//        vradarObj[tempObjID].set_object_arellatrms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch0_rx.Obj_2_Quality_ch0.Obj_ArelLat_rms));
+//        vradarObj[tempObjID].set_object_arellongrms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch0_rx.Obj_2_Quality_ch0.Obj_ArelLong_rms));
+//        vradarObj[tempObjID].set_object_orientationrms(this->Trans_Ori_RMS_Ro_To_Phy(ars408_can_database_ch0_rx.Obj_2_Quality_ch0.Obj_Orientation_rms));
+//        vradarObj[tempObjID].set_object_measurestate(ars408_can_database_ch0_rx.Obj_2_Quality_ch0.Obj_MeasState);
+//        vradarObj[tempObjID].set_object_probofexist(this->Trans_ProbOfExist_Ro_To_Phy(ars408_can_database_ch0_rx.Obj_2_Quality_ch0.Obj_ProbOfExist));
+//        break;
+//    case 0x60D:
+//        tempObjID = ars408_can_database_ch0_rx.Obj_3_Extended_ch0.Obj_ID;
+//        tempAX = -ars408_can_database_ch0_rx.Obj_3_Extended_ch0.Obj_ArelLat_phys;
+//        tempAY = ars408_can_database_ch0_rx.Obj_3_Extended_ch0.Obj_ArelLong_phys;
+//        this->Rotate_Translate(tempAX,tempAY,setupConfig.radarAzimuth,setupConfig.radarOffsetX,setupConfig.radarOffsetY);
+//        vradarObj[tempObjID].set_object_arellong(tempAY);
+//        vradarObj[tempObjID].set_object_arellat(tempAX);
+//        tempOri = ars408_can_database_ch0_rx.Obj_3_Extended_ch0.Obj_OrientationAngle_phys + setupConfig.radarAzimuth;
+//        if(tempOri > 180.0)tempOri = tempOri - 360.0;
+//        if(tempOri < -180.0)tempOri = tempOri + 360.0;
+//        vradarObj[tempObjID].set_object_orientationangle(tempOri);
+//        vradarObj[tempObjID].set_object_class(ars408_can_database_ch0_rx.Obj_3_Extended_ch0.Obj_Class);
+//        vradarObj[tempObjID].set_object_length(ars408_can_database_ch0_rx.Obj_3_Extended_ch0.Obj_Length_phys);
+//        vradarObj[tempObjID].set_object_width(ars408_can_database_ch0_rx.Obj_3_Extended_ch0.Obj_Width_phys);
+//        break;
+//    default:
+//        break;
+//    }
+//}
+
+//void CANRecv_Consumer::Pack_Info_To_SHM_ch1(uint32_t can_id)
+//{
+//    std::string major,minor,patch;
+//    iv::radar::radarobject *pobj;
+//    iv::radar::radarobject xradarObj_null;
+//    double tempDX,tempDY,tempVX,tempVY,tempAX,tempAY,tempOri;
+//    uint8_t tempObjID;
+
+//    switch (can_id - 0x010) {
+//    case 0x201:
+//        persistent_Error = ars408_can_database_ch1_rx.RadarState_ch1.RadarState_Persistent_Error;
+//        interference_Error = ars408_can_database_ch1_rx.RadarState_ch1.RadarState_Interference;
+//        temperature_Error = ars408_can_database_ch1_rx.RadarState_ch1.RadarState_Temperature_Error;
+//        temporary_Error = ars408_can_database_ch1_rx.RadarState_ch1.RadarState_Temporary_Error;
+//        voltage_Error = ars408_can_database_ch1_rx.RadarState_ch1.RadarState_Voltage_Error;
+//        speed_Loss = ars408_can_database_ch1_rx.RadarState_ch1.RadarState_MotionRxState & 0x01;
+//        yaw_Rate_Loss = (ars408_can_database_ch1_rx.RadarState_ch1.RadarState_MotionRxState >> 1) & 0x01;
+//        break;
+//    case 0x700:
+//        major = std::to_string((unsigned int)ars408_can_database_ch1_rx.VersionID_ch1.Version_MajorRelease);
+//        minor = std::to_string((unsigned int)ars408_can_database_ch1_rx.VersionID_ch1.Version_MinorRelease);
+//        patch = std::to_string((unsigned int)ars408_can_database_ch1_rx.VersionID_ch1.Version_PatchLevel);
+//        radar_Version = major + "." + minor + "." + patch;
+//        break;
+//    case 0x60A:
+//        if(ars408_can_database_ch1_rx.Obj_0_Status_ch1.Obj_NofObjects == 0)
+//        {
+//            xradarObjArray.Clear();
+//            xradarObjArray.set_mstime(QDateTime::currentMSecsSinceEpoch());
+//            xradarObjArray.set_persistent_error(persistent_Error);
+//            xradarObjArray.set_interference_error(interference_Error);
+//            xradarObjArray.set_temperature_error(temperature_Error);
+//            xradarObjArray.set_temporary_error(temporary_Error);
+//            xradarObjArray.set_voltage_error(voltage_Error);
+//            xradarObjArray.set_speed_loss(speed_Loss);
+//            xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
+//            xradarObjArray.set_radar_version(radar_Version);
+
+//            radarObjArraySend_lock.lock();
+//            radarObjArray_send.CopyFrom(xradarObjArray);
+//            radarObjArraySend_lock.unlock();
+//            emit RadarObjectArray_Ready();
+//        }
+//        else
+//        {
+//            xradarObjArray.Clear();
+//            for(int i=0;i<RADAR_OBJ_MAX_NUM;i++)
+//            {
+//                if(radarObjFreshFlag[i] == true)
+//                {
+//                    pobj = xradarObjArray.add_obj();
+//                    pobj->CopyFrom(vradarObj[i]);
+//                }
+//            }
+//            xradarObjArray.set_mstime(QDateTime::currentMSecsSinceEpoch());
+//            xradarObjArray.set_persistent_error(persistent_Error);
+//            xradarObjArray.set_interference_error(interference_Error);
+//            xradarObjArray.set_temperature_error(temperature_Error);
+//            xradarObjArray.set_temporary_error(temporary_Error);
+//            xradarObjArray.set_voltage_error(voltage_Error);
+//            xradarObjArray.set_speed_loss(speed_Loss);
+//            xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
+//            xradarObjArray.set_radar_version(radar_Version);
+
+//            radarObjArraySend_lock.lock();
+//            radarObjArray_send.CopyFrom(xradarObjArray);
+//            radarObjArraySend_lock.unlock();
+////            std::cout<<radarObjArray_send.obj_size()<<std::endl;
+//            emit RadarObjectArray_Ready();
+//        }
+//        //clear the obj vector and flag vector
+//        vradarObj.fill(xradarObj_null,RADAR_OBJ_MAX_NUM);
+//        radarObjFreshFlag.fill(false,RADAR_OBJ_MAX_NUM);
+//        break;
+//    case 0x60B:
+//        tempObjID = ars408_can_database_ch1_rx.Obj_1_General_ch1.Obj_ID;
+//        radarObjFreshFlag[tempObjID] = true;
+//        tempDX = -ars408_can_database_ch1_rx.Obj_1_General_ch1.Obj_DistLat_phys;
+//        tempDY = ars408_can_database_ch1_rx.Obj_1_General_ch1.Obj_DistLong_phys;
+//        this->Rotate_Translate(tempDX,tempDY,setupConfig.radarAzimuth,setupConfig.radarOffsetX,setupConfig.radarOffsetY);
+//        vradarObj[tempObjID].set_x(tempDX);
+//        vradarObj[tempObjID].set_y(tempDY);
+//        tempVX = -ars408_can_database_ch1_rx.Obj_1_General_ch1.Obj_VrelLat_phys;
+//        tempVY = ars408_can_database_ch1_rx.Obj_1_General_ch1.Obj_VrelLong_phys;
+//        this->Rotate_Translate(tempVX,tempVY,setupConfig.radarAzimuth,setupConfig.radarOffsetX,setupConfig.radarOffsetY);
+//        vradarObj[tempObjID].set_vx(tempVX);
+//        vradarObj[tempObjID].set_vy(tempVY);
+//        vradarObj[tempObjID].set_vel(sqrt(tempVX*tempVX+tempVY*tempVY));
+//        vradarObj[tempObjID].set_bvalid(true);
+//        vradarObj[tempObjID].set_id(tempObjID);
+//        vradarObj[tempObjID].set_dynamic_property(ars408_can_database_ch1_rx.Obj_1_General_ch1.Obj_DynProp);
+//        vradarObj[tempObjID].set_rcs_radarcrosssection(ars408_can_database_ch1_rx.Obj_1_General_ch1.Obj_RCS_phys);
+//        break;
+//    case 0x60C:
+//        tempObjID = ars408_can_database_ch1_rx.Obj_2_Quality_ch1.Obj_ID;
+//        vradarObj[tempObjID].set_distlong_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch1_rx.Obj_2_Quality_ch1.Obj_DistLong_rms));
+//        vradarObj[tempObjID].set_distlat_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch1_rx.Obj_2_Quality_ch1.Obj_DistLat_rms));
+//        vradarObj[tempObjID].set_vrellong_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch1_rx.Obj_2_Quality_ch1.Obj_VrelLong_rms));
+//        vradarObj[tempObjID].set_vrellat_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch1_rx.Obj_2_Quality_ch1.Obj_VrelLat_rms));
+//        vradarObj[tempObjID].set_object_arellatrms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch1_rx.Obj_2_Quality_ch1.Obj_ArelLat_rms));
+//        vradarObj[tempObjID].set_object_arellongrms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch1_rx.Obj_2_Quality_ch1.Obj_ArelLong_rms));
+//        vradarObj[tempObjID].set_object_orientationrms(this->Trans_Ori_RMS_Ro_To_Phy(ars408_can_database_ch1_rx.Obj_2_Quality_ch1.Obj_Orientation_rms));
+//        vradarObj[tempObjID].set_object_measurestate(ars408_can_database_ch1_rx.Obj_2_Quality_ch1.Obj_MeasState);
+//        vradarObj[tempObjID].set_object_probofexist(this->Trans_ProbOfExist_Ro_To_Phy(ars408_can_database_ch1_rx.Obj_2_Quality_ch1.Obj_ProbOfExist));
+//        break;
+//    case 0x60D:
+//        tempObjID = ars408_can_database_ch1_rx.Obj_3_Extended_ch1.Obj_ID;
+//        tempAX = -ars408_can_database_ch1_rx.Obj_3_Extended_ch1.Obj_ArelLat_phys;
+//        tempAY = ars408_can_database_ch1_rx.Obj_3_Extended_ch1.Obj_ArelLong_phys;
+//        this->Rotate_Translate(tempAX,tempAY,setupConfig.radarAzimuth,setupConfig.radarOffsetX,setupConfig.radarOffsetY);
+//        vradarObj[tempObjID].set_object_arellong(tempAY);
+//        vradarObj[tempObjID].set_object_arellat(tempAX);
+//        tempOri = ars408_can_database_ch1_rx.Obj_3_Extended_ch1.Obj_OrientationAngle_phys + setupConfig.radarAzimuth;
+//        if(tempOri > 180.0)tempOri = tempOri - 360.0;
+//        if(tempOri < -180.0)tempOri = tempOri + 360.0;
+//        vradarObj[tempObjID].set_object_orientationangle(tempOri);
+//        vradarObj[tempObjID].set_object_class(ars408_can_database_ch1_rx.Obj_3_Extended_ch1.Obj_Class);
+//        vradarObj[tempObjID].set_object_length(ars408_can_database_ch1_rx.Obj_3_Extended_ch1.Obj_Length_phys);
+//        vradarObj[tempObjID].set_object_width(ars408_can_database_ch1_rx.Obj_3_Extended_ch1.Obj_Width_phys);
+//        break;
+//    default:
+//        break;
+//    }
+//}
+
+//void CANRecv_Consumer::Pack_Info_To_SHM_ch2(uint32_t can_id)
+//{
+//    std::string major,minor,patch;
+//    iv::radar::radarobject *pobj;
+//    iv::radar::radarobject xradarObj_null;
+//    double tempDX,tempDY,tempVX,tempVY,tempAX,tempAY,tempOri;
+//    uint8_t tempObjID;
+
+//    switch (can_id - 0x020) {
+//    case 0x201:
+//        persistent_Error = ars408_can_database_ch2_rx.RadarState_ch2.RadarState_Persistent_Error;
+//        interference_Error = ars408_can_database_ch2_rx.RadarState_ch2.RadarState_Interference;
+//        temperature_Error = ars408_can_database_ch2_rx.RadarState_ch2.RadarState_Temperature_Error;
+//        temporary_Error = ars408_can_database_ch2_rx.RadarState_ch2.RadarState_Temporary_Error;
+//        voltage_Error = ars408_can_database_ch2_rx.RadarState_ch2.RadarState_Voltage_Error;
+//        speed_Loss = ars408_can_database_ch2_rx.RadarState_ch2.RadarState_MotionRxState & 0x01;
+//        yaw_Rate_Loss = (ars408_can_database_ch2_rx.RadarState_ch2.RadarState_MotionRxState >> 1) & 0x01;
+//        break;
+//    case 0x700:
+//        major = std::to_string((unsigned int)ars408_can_database_ch2_rx.VersionID_ch2.Version_MajorRelease);
+//        minor = std::to_string((unsigned int)ars408_can_database_ch2_rx.VersionID_ch2.Version_MinorRelease);
+//        patch = std::to_string((unsigned int)ars408_can_database_ch2_rx.VersionID_ch2.Version_PatchLevel);
+//        radar_Version = major + "." + minor + "." + patch;
+//        break;
+//    case 0x60A:
+//        if(ars408_can_database_ch2_rx.Obj_0_Status_ch2.Obj_NofObjects == 0)
+//        {
+//            xradarObjArray.Clear();
+//            xradarObjArray.set_mstime(QDateTime::currentMSecsSinceEpoch());
+//            xradarObjArray.set_persistent_error(persistent_Error);
+//            xradarObjArray.set_interference_error(interference_Error);
+//            xradarObjArray.set_temperature_error(temperature_Error);
+//            xradarObjArray.set_temporary_error(temporary_Error);
+//            xradarObjArray.set_voltage_error(voltage_Error);
+//            xradarObjArray.set_speed_loss(speed_Loss);
+//            xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
+//            xradarObjArray.set_radar_version(radar_Version);
+
+//            radarObjArraySend_lock.lock();
+//            radarObjArray_send.CopyFrom(xradarObjArray);
+//            radarObjArraySend_lock.unlock();
+//            emit RadarObjectArray_Ready();
+//        }
+//        else
+//        {
+//            xradarObjArray.Clear();
+//            for(int i=0;i<RADAR_OBJ_MAX_NUM;i++)
+//            {
+//                if(radarObjFreshFlag[i] == true)
+//                {
+//                    pobj = xradarObjArray.add_obj();
+//                    pobj->CopyFrom(vradarObj[i]);
+//                }
+//            }
+//            xradarObjArray.set_mstime(QDateTime::currentMSecsSinceEpoch());
+//            xradarObjArray.set_persistent_error(persistent_Error);
+//            xradarObjArray.set_interference_error(interference_Error);
+//            xradarObjArray.set_temperature_error(temperature_Error);
+//            xradarObjArray.set_temporary_error(temporary_Error);
+//            xradarObjArray.set_voltage_error(voltage_Error);
+//            xradarObjArray.set_speed_loss(speed_Loss);
+//            xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
+//            xradarObjArray.set_radar_version(radar_Version);
+
+//            radarObjArraySend_lock.lock();
+//            radarObjArray_send.CopyFrom(xradarObjArray);
+//            radarObjArraySend_lock.unlock();
+////            std::cout<<radarObjArray_send.obj_size()<<std::endl;
+//            emit RadarObjectArray_Ready();
+//        }
+//        //clear the obj vector and flag vector
+//        vradarObj.fill(xradarObj_null,RADAR_OBJ_MAX_NUM);
+//        radarObjFreshFlag.fill(false,RADAR_OBJ_MAX_NUM);
+//        break;
+//    case 0x60B:
+//        tempObjID = ars408_can_database_ch2_rx.Obj_1_General_ch2.Obj_ID;
+//        radarObjFreshFlag[tempObjID] = true;
+//        tempDX = -ars408_can_database_ch2_rx.Obj_1_General_ch2.Obj_DistLat_phys;
+//        tempDY = ars408_can_database_ch2_rx.Obj_1_General_ch2.Obj_DistLong_phys;
+//        this->Rotate_Translate(tempDX,tempDY,setupConfig.radarAzimuth,setupConfig.radarOffsetX,setupConfig.radarOffsetY);
+//        vradarObj[tempObjID].set_x(tempDX);
+//        vradarObj[tempObjID].set_y(tempDY);
+//        tempVX = -ars408_can_database_ch2_rx.Obj_1_General_ch2.Obj_VrelLat_phys;
+//        tempVY = ars408_can_database_ch2_rx.Obj_1_General_ch2.Obj_VrelLong_phys;
+//        this->Rotate_Translate(tempVX,tempVY,setupConfig.radarAzimuth,setupConfig.radarOffsetX,setupConfig.radarOffsetY);
+//        vradarObj[tempObjID].set_vx(tempVX);
+//        vradarObj[tempObjID].set_vy(tempVY);
+//        vradarObj[tempObjID].set_vel(sqrt(tempVX*tempVX+tempVY*tempVY));
+//        vradarObj[tempObjID].set_bvalid(true);
+//        vradarObj[tempObjID].set_id(tempObjID);
+//        vradarObj[tempObjID].set_dynamic_property(ars408_can_database_ch2_rx.Obj_1_General_ch2.Obj_DynProp);
+//        vradarObj[tempObjID].set_rcs_radarcrosssection(ars408_can_database_ch2_rx.Obj_1_General_ch2.Obj_RCS_phys);
+//        break;
+//    case 0x60C:
+//        tempObjID = ars408_can_database_ch2_rx.Obj_2_Quality_ch2.Obj_ID;
+//        vradarObj[tempObjID].set_distlong_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch2_rx.Obj_2_Quality_ch2.Obj_DistLong_rms));
+//        vradarObj[tempObjID].set_distlat_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch2_rx.Obj_2_Quality_ch2.Obj_DistLat_rms));
+//        vradarObj[tempObjID].set_vrellong_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch2_rx.Obj_2_Quality_ch2.Obj_VrelLong_rms));
+//        vradarObj[tempObjID].set_vrellat_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch2_rx.Obj_2_Quality_ch2.Obj_VrelLat_rms));
+//        vradarObj[tempObjID].set_object_arellatrms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch2_rx.Obj_2_Quality_ch2.Obj_ArelLat_rms));
+//        vradarObj[tempObjID].set_object_arellongrms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch2_rx.Obj_2_Quality_ch2.Obj_ArelLong_rms));
+//        vradarObj[tempObjID].set_object_orientationrms(this->Trans_Ori_RMS_Ro_To_Phy(ars408_can_database_ch2_rx.Obj_2_Quality_ch2.Obj_Orientation_rms));
+//        vradarObj[tempObjID].set_object_measurestate(ars408_can_database_ch2_rx.Obj_2_Quality_ch2.Obj_MeasState);
+//        vradarObj[tempObjID].set_object_probofexist(this->Trans_ProbOfExist_Ro_To_Phy(ars408_can_database_ch2_rx.Obj_2_Quality_ch2.Obj_ProbOfExist));
+//        break;
+//    case 0x60D:
+//        tempObjID = ars408_can_database_ch2_rx.Obj_3_Extended_ch2.Obj_ID;
+//        tempAX = -ars408_can_database_ch2_rx.Obj_3_Extended_ch2.Obj_ArelLat_phys;
+//        tempAY = ars408_can_database_ch2_rx.Obj_3_Extended_ch2.Obj_ArelLong_phys;
+//        this->Rotate_Translate(tempAX,tempAY,setupConfig.radarAzimuth,setupConfig.radarOffsetX,setupConfig.radarOffsetY);
+//        vradarObj[tempObjID].set_object_arellong(tempAY);
+//        vradarObj[tempObjID].set_object_arellat(tempAX);
+//        tempOri = ars408_can_database_ch2_rx.Obj_3_Extended_ch2.Obj_OrientationAngle_phys + setupConfig.radarAzimuth;
+//        if(tempOri > 180.0)tempOri = tempOri - 360.0;
+//        if(tempOri < -180.0)tempOri = tempOri + 360.0;
+//        vradarObj[tempObjID].set_object_orientationangle(tempOri);
+//        vradarObj[tempObjID].set_object_class(ars408_can_database_ch2_rx.Obj_3_Extended_ch2.Obj_Class);
+//        vradarObj[tempObjID].set_object_length(ars408_can_database_ch2_rx.Obj_3_Extended_ch2.Obj_Length_phys);
+//        vradarObj[tempObjID].set_object_width(ars408_can_database_ch2_rx.Obj_3_Extended_ch2.Obj_Width_phys);
+//        break;
+//    default:
+//        break;
+//    }
+//}
+
+//void CANRecv_Consumer::Pack_Info_To_SHM_ch3(uint32_t can_id)
+//{
+//    std::string major,minor,patch;
+//    iv::radar::radarobject *pobj;
+//    iv::radar::radarobject xradarObj_null;
+//    double tempDX,tempDY,tempVX,tempVY,tempAX,tempAY,tempOri;
+//    uint8_t tempObjID;
+
+//    switch (can_id - 0x030) {
+//    case 0x201:
+//        persistent_Error = ars408_can_database_ch3_rx.RadarState_ch3.RadarState_Persistent_Error;
+//        interference_Error = ars408_can_database_ch3_rx.RadarState_ch3.RadarState_Interference;
+//        temperature_Error = ars408_can_database_ch3_rx.RadarState_ch3.RadarState_Temperature_Error;
+//        temporary_Error = ars408_can_database_ch3_rx.RadarState_ch3.RadarState_Temporary_Error;
+//        voltage_Error = ars408_can_database_ch3_rx.RadarState_ch3.RadarState_Voltage_Error;
+//        speed_Loss = ars408_can_database_ch3_rx.RadarState_ch3.RadarState_MotionRxState & 0x01;
+//        yaw_Rate_Loss = (ars408_can_database_ch3_rx.RadarState_ch3.RadarState_MotionRxState >> 1) & 0x01;
+//        break;
+//    case 0x700:
+//        major = std::to_string((unsigned int)ars408_can_database_ch3_rx.VersionID_ch3.Version_MajorRelease);
+//        minor = std::to_string((unsigned int)ars408_can_database_ch3_rx.VersionID_ch3.Version_MinorRelease);
+//        patch = std::to_string((unsigned int)ars408_can_database_ch3_rx.VersionID_ch3.Version_PatchLevel);
+//        radar_Version = major + "." + minor + "." + patch;
+//        break;
+//    case 0x60A:
+//        if(ars408_can_database_ch3_rx.Obj_0_Status_ch3.Obj_NofObjects == 0)
+//        {
+//            xradarObjArray.Clear();
+//            xradarObjArray.set_mstime(QDateTime::currentMSecsSinceEpoch());
+//            xradarObjArray.set_persistent_error(persistent_Error);
+//            xradarObjArray.set_interference_error(interference_Error);
+//            xradarObjArray.set_temperature_error(temperature_Error);
+//            xradarObjArray.set_temporary_error(temporary_Error);
+//            xradarObjArray.set_voltage_error(voltage_Error);
+//            xradarObjArray.set_speed_loss(speed_Loss);
+//            xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
+//            xradarObjArray.set_radar_version(radar_Version);
+
+//            radarObjArraySend_lock.lock();
+//            radarObjArray_send.CopyFrom(xradarObjArray);
+//            radarObjArraySend_lock.unlock();
+//            emit RadarObjectArray_Ready();
+//        }
+//        else
+//        {
+//            xradarObjArray.Clear();
+//            for(int i=0;i<RADAR_OBJ_MAX_NUM;i++)
+//            {
+//                if(radarObjFreshFlag[i] == true)
+//                {
+//                    pobj = xradarObjArray.add_obj();
+//                    pobj->CopyFrom(vradarObj[i]);
+//                }
+//            }
+//            xradarObjArray.set_mstime(QDateTime::currentMSecsSinceEpoch());
+//            xradarObjArray.set_persistent_error(persistent_Error);
+//            xradarObjArray.set_interference_error(interference_Error);
+//            xradarObjArray.set_temperature_error(temperature_Error);
+//            xradarObjArray.set_temporary_error(temporary_Error);
+//            xradarObjArray.set_voltage_error(voltage_Error);
+//            xradarObjArray.set_speed_loss(speed_Loss);
+//            xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
+//            xradarObjArray.set_radar_version(radar_Version);
+
+//            radarObjArraySend_lock.lock();
+//            radarObjArray_send.CopyFrom(xradarObjArray);
+//            radarObjArraySend_lock.unlock();
+////            std::cout<<radarObjArray_send.obj_size()<<std::endl;
+//            emit RadarObjectArray_Ready();
+//        }
+//        //clear the obj vector and flag vector
+//        vradarObj.fill(xradarObj_null,RADAR_OBJ_MAX_NUM);
+//        radarObjFreshFlag.fill(false,RADAR_OBJ_MAX_NUM);
+//        break;
+//    case 0x60B:
+//        tempObjID = ars408_can_database_ch3_rx.Obj_1_General_ch3.Obj_ID;
+//        radarObjFreshFlag[tempObjID] = true;
+//        tempDX = -ars408_can_database_ch3_rx.Obj_1_General_ch3.Obj_DistLat_phys;
+//        tempDY = ars408_can_database_ch3_rx.Obj_1_General_ch3.Obj_DistLong_phys;
+//        this->Rotate_Translate(tempDX,tempDY,setupConfig.radarAzimuth,setupConfig.radarOffsetX,setupConfig.radarOffsetY);
+//        vradarObj[tempObjID].set_x(tempDX);
+//        vradarObj[tempObjID].set_y(tempDY);
+//        tempVX = -ars408_can_database_ch3_rx.Obj_1_General_ch3.Obj_VrelLat_phys;
+//        tempVY = ars408_can_database_ch3_rx.Obj_1_General_ch3.Obj_VrelLong_phys;
+//        this->Rotate_Translate(tempVX,tempVY,setupConfig.radarAzimuth,setupConfig.radarOffsetX,setupConfig.radarOffsetY);
+//        vradarObj[tempObjID].set_vx(tempVX);
+//        vradarObj[tempObjID].set_vy(tempVY);
+//        vradarObj[tempObjID].set_vel(sqrt(tempVX*tempVX+tempVY*tempVY));
+//        vradarObj[tempObjID].set_bvalid(true);
+//        vradarObj[tempObjID].set_id(tempObjID);
+//        vradarObj[tempObjID].set_dynamic_property(ars408_can_database_ch3_rx.Obj_1_General_ch3.Obj_DynProp);
+//        vradarObj[tempObjID].set_rcs_radarcrosssection(ars408_can_database_ch3_rx.Obj_1_General_ch3.Obj_RCS_phys);
+//        break;
+//    case 0x60C:
+//        tempObjID = ars408_can_database_ch3_rx.Obj_2_Quality_ch3.Obj_ID;
+//        vradarObj[tempObjID].set_distlong_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch3_rx.Obj_2_Quality_ch3.Obj_DistLong_rms));
+//        vradarObj[tempObjID].set_distlat_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch3_rx.Obj_2_Quality_ch3.Obj_DistLat_rms));
+//        vradarObj[tempObjID].set_vrellong_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch3_rx.Obj_2_Quality_ch3.Obj_VrelLong_rms));
+//        vradarObj[tempObjID].set_vrellat_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch3_rx.Obj_2_Quality_ch3.Obj_VrelLat_rms));
+//        vradarObj[tempObjID].set_object_arellatrms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch3_rx.Obj_2_Quality_ch3.Obj_ArelLat_rms));
+//        vradarObj[tempObjID].set_object_arellongrms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch3_rx.Obj_2_Quality_ch3.Obj_ArelLong_rms));
+//        vradarObj[tempObjID].set_object_orientationrms(this->Trans_Ori_RMS_Ro_To_Phy(ars408_can_database_ch3_rx.Obj_2_Quality_ch3.Obj_Orientation_rms));
+//        vradarObj[tempObjID].set_object_measurestate(ars408_can_database_ch3_rx.Obj_2_Quality_ch3.Obj_MeasState);
+//        vradarObj[tempObjID].set_object_probofexist(this->Trans_ProbOfExist_Ro_To_Phy(ars408_can_database_ch3_rx.Obj_2_Quality_ch3.Obj_ProbOfExist));
+//        break;
+//    case 0x60D:
+//        tempObjID = ars408_can_database_ch3_rx.Obj_3_Extended_ch3.Obj_ID;
+//        tempAX = -ars408_can_database_ch3_rx.Obj_3_Extended_ch3.Obj_ArelLat_phys;
+//        tempAY = ars408_can_database_ch3_rx.Obj_3_Extended_ch3.Obj_ArelLong_phys;
+//        this->Rotate_Translate(tempAX,tempAY,setupConfig.radarAzimuth,setupConfig.radarOffsetX,setupConfig.radarOffsetY);
+//        vradarObj[tempObjID].set_object_arellong(tempAY);
+//        vradarObj[tempObjID].set_object_arellat(tempAX);
+//        tempOri = ars408_can_database_ch3_rx.Obj_3_Extended_ch3.Obj_OrientationAngle_phys + setupConfig.radarAzimuth;
+//        if(tempOri > 180.0)tempOri = tempOri - 360.0;
+//        if(tempOri < -180.0)tempOri = tempOri + 360.0;
+//        vradarObj[tempObjID].set_object_orientationangle(tempOri);
+//        vradarObj[tempObjID].set_object_class(ars408_can_database_ch3_rx.Obj_3_Extended_ch3.Obj_Class);
+//        vradarObj[tempObjID].set_object_length(ars408_can_database_ch3_rx.Obj_3_Extended_ch3.Obj_Length_phys);
+//        vradarObj[tempObjID].set_object_width(ars408_can_database_ch3_rx.Obj_3_Extended_ch3.Obj_Width_phys);
+//        break;
+//    default:
+//        break;
+//    }
+//}
+
+//void CANRecv_Consumer::Pack_Info_To_SHM_ch4(uint32_t can_id)
+//{
+//    std::string major,minor,patch;
+//    iv::radar::radarobject *pobj;
+//    iv::radar::radarobject xradarObj_null;
+//    double tempDX,tempDY,tempVX,tempVY,tempAX,tempAY,tempOri;
+//    uint8_t tempObjID;
+
+//    switch (can_id - 0x040) {
+//    case 0x201:
+//        persistent_Error = ars408_can_database_ch4_rx.RadarState_ch4.RadarState_Persistent_Error;
+//        interference_Error = ars408_can_database_ch4_rx.RadarState_ch4.RadarState_Interference;
+//        temperature_Error = ars408_can_database_ch4_rx.RadarState_ch4.RadarState_Temperature_Error;
+//        temporary_Error = ars408_can_database_ch4_rx.RadarState_ch4.RadarState_Temporary_Error;
+//        voltage_Error = ars408_can_database_ch4_rx.RadarState_ch4.RadarState_Voltage_Error;
+//        speed_Loss = ars408_can_database_ch4_rx.RadarState_ch4.RadarState_MotionRxState & 0x01;
+//        yaw_Rate_Loss = (ars408_can_database_ch4_rx.RadarState_ch4.RadarState_MotionRxState >> 1) & 0x01;
+//        break;
+//    case 0x700:
+//        major = std::to_string((unsigned int)ars408_can_database_ch4_rx.VersionID_ch4.Version_MajorRelease);
+//        minor = std::to_string((unsigned int)ars408_can_database_ch4_rx.VersionID_ch4.Version_MinorRelease);
+//        patch = std::to_string((unsigned int)ars408_can_database_ch4_rx.VersionID_ch4.Version_PatchLevel);
+//        radar_Version = major + "." + minor + "." + patch;
+//        break;
+//    case 0x60A:
+//        if(ars408_can_database_ch4_rx.Obj_0_Status_ch4.Obj_NofObjects == 0)
+//        {
+//            xradarObjArray.Clear();
+//            xradarObjArray.set_mstime(QDateTime::currentMSecsSinceEpoch());
+//            xradarObjArray.set_persistent_error(persistent_Error);
+//            xradarObjArray.set_interference_error(interference_Error);
+//            xradarObjArray.set_temperature_error(temperature_Error);
+//            xradarObjArray.set_temporary_error(temporary_Error);
+//            xradarObjArray.set_voltage_error(voltage_Error);
+//            xradarObjArray.set_speed_loss(speed_Loss);
+//            xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
+//            xradarObjArray.set_radar_version(radar_Version);
+
+//            radarObjArraySend_lock.lock();
+//            radarObjArray_send.CopyFrom(xradarObjArray);
+//            radarObjArraySend_lock.unlock();
+//            emit RadarObjectArray_Ready();
+//        }
+//        else
+//        {
+//            xradarObjArray.Clear();
+//            for(int i=0;i<RADAR_OBJ_MAX_NUM;i++)
+//            {
+//                if(radarObjFreshFlag[i] == true)
+//                {
+//                    pobj = xradarObjArray.add_obj();
+//                    pobj->CopyFrom(vradarObj[i]);
+//                }
+//            }
+//            xradarObjArray.set_mstime(QDateTime::currentMSecsSinceEpoch());
+//            xradarObjArray.set_persistent_error(persistent_Error);
+//            xradarObjArray.set_interference_error(interference_Error);
+//            xradarObjArray.set_temperature_error(temperature_Error);
+//            xradarObjArray.set_temporary_error(temporary_Error);
+//            xradarObjArray.set_voltage_error(voltage_Error);
+//            xradarObjArray.set_speed_loss(speed_Loss);
+//            xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
+//            xradarObjArray.set_radar_version(radar_Version);
+
+//            radarObjArraySend_lock.lock();
+//            radarObjArray_send.CopyFrom(xradarObjArray);
+//            radarObjArraySend_lock.unlock();
+////            std::cout<<radarObjArray_send.obj_size()<<std::endl;
+//            emit RadarObjectArray_Ready();
+//        }
+//        //clear the obj vector and flag vector
+//        vradarObj.fill(xradarObj_null,RADAR_OBJ_MAX_NUM);
+//        radarObjFreshFlag.fill(false,RADAR_OBJ_MAX_NUM);
+//        break;
+//    case 0x60B:
+//        tempObjID = ars408_can_database_ch4_rx.Obj_1_General_ch4.Obj_ID;
+//        radarObjFreshFlag[tempObjID] = true;
+//        tempDX = -ars408_can_database_ch4_rx.Obj_1_General_ch4.Obj_DistLat_phys;
+//        tempDY = ars408_can_database_ch4_rx.Obj_1_General_ch4.Obj_DistLong_phys;
+//        this->Rotate_Translate(tempDX,tempDY,setupConfig.radarAzimuth,setupConfig.radarOffsetX,setupConfig.radarOffsetY);
+//        vradarObj[tempObjID].set_x(tempDX);
+//        vradarObj[tempObjID].set_y(tempDY);
+//        tempVX = -ars408_can_database_ch4_rx.Obj_1_General_ch4.Obj_VrelLat_phys;
+//        tempVY = ars408_can_database_ch4_rx.Obj_1_General_ch4.Obj_VrelLong_phys;
+//        this->Rotate_Translate(tempVX,tempVY,setupConfig.radarAzimuth,setupConfig.radarOffsetX,setupConfig.radarOffsetY);
+//        vradarObj[tempObjID].set_vx(tempVX);
+//        vradarObj[tempObjID].set_vy(tempVY);
+//        vradarObj[tempObjID].set_vel(sqrt(tempVX*tempVX+tempVY*tempVY));
+//        vradarObj[tempObjID].set_bvalid(true);
+//        vradarObj[tempObjID].set_id(tempObjID);
+//        vradarObj[tempObjID].set_dynamic_property(ars408_can_database_ch4_rx.Obj_1_General_ch4.Obj_DynProp);
+//        vradarObj[tempObjID].set_rcs_radarcrosssection(ars408_can_database_ch4_rx.Obj_1_General_ch4.Obj_RCS_phys);
+//        break;
+//    case 0x60C:
+//        tempObjID = ars408_can_database_ch4_rx.Obj_2_Quality_ch4.Obj_ID;
+//        vradarObj[tempObjID].set_distlong_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch4_rx.Obj_2_Quality_ch4.Obj_DistLong_rms));
+//        vradarObj[tempObjID].set_distlat_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch4_rx.Obj_2_Quality_ch4.Obj_DistLat_rms));
+//        vradarObj[tempObjID].set_vrellong_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch4_rx.Obj_2_Quality_ch4.Obj_VrelLong_rms));
+//        vradarObj[tempObjID].set_vrellat_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch4_rx.Obj_2_Quality_ch4.Obj_VrelLat_rms));
+//        vradarObj[tempObjID].set_object_arellatrms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch4_rx.Obj_2_Quality_ch4.Obj_ArelLat_rms));
+//        vradarObj[tempObjID].set_object_arellongrms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch4_rx.Obj_2_Quality_ch4.Obj_ArelLong_rms));
+//        vradarObj[tempObjID].set_object_orientationrms(this->Trans_Ori_RMS_Ro_To_Phy(ars408_can_database_ch4_rx.Obj_2_Quality_ch4.Obj_Orientation_rms));
+//        vradarObj[tempObjID].set_object_measurestate(ars408_can_database_ch4_rx.Obj_2_Quality_ch4.Obj_MeasState);
+//        vradarObj[tempObjID].set_object_probofexist(this->Trans_ProbOfExist_Ro_To_Phy(ars408_can_database_ch4_rx.Obj_2_Quality_ch4.Obj_ProbOfExist));
+//        break;
+//    case 0x60D:
+//        tempObjID = ars408_can_database_ch4_rx.Obj_3_Extended_ch4.Obj_ID;
+//        tempAX = -ars408_can_database_ch4_rx.Obj_3_Extended_ch4.Obj_ArelLat_phys;
+//        tempAY = ars408_can_database_ch4_rx.Obj_3_Extended_ch4.Obj_ArelLong_phys;
+//        this->Rotate_Translate(tempAX,tempAY,setupConfig.radarAzimuth,setupConfig.radarOffsetX,setupConfig.radarOffsetY);
+//        vradarObj[tempObjID].set_object_arellong(tempAY);
+//        vradarObj[tempObjID].set_object_arellat(tempAX);
+//        tempOri = ars408_can_database_ch4_rx.Obj_3_Extended_ch4.Obj_OrientationAngle_phys + setupConfig.radarAzimuth;
+//        if(tempOri > 180.0)tempOri = tempOri - 360.0;
+//        if(tempOri < -180.0)tempOri = tempOri + 360.0;
+//        vradarObj[tempObjID].set_object_orientationangle(tempOri);
+//        vradarObj[tempObjID].set_object_class(ars408_can_database_ch4_rx.Obj_3_Extended_ch4.Obj_Class);
+//        vradarObj[tempObjID].set_object_length(ars408_can_database_ch4_rx.Obj_3_Extended_ch4.Obj_Length_phys);
+//        vradarObj[tempObjID].set_object_width(ars408_can_database_ch4_rx.Obj_3_Extended_ch4.Obj_Width_phys);
+//        break;
+//    default:
+//        break;
+//    }
+//}
+
+//void CANRecv_Consumer::Pack_Info_To_SHM_ch5(uint32_t can_id)
+//{
+//    std::string major,minor,patch;
+//    iv::radar::radarobject *pobj;
+//    iv::radar::radarobject xradarObj_null;
+//    double tempDX,tempDY,tempVX,tempVY,tempAX,tempAY,tempOri;
+//    uint8_t tempObjID;
+
+//    switch (can_id - 0x050) {
+//    case 0x201:
+//        persistent_Error = ars408_can_database_ch5_rx.RadarState_ch5.RadarState_Persistent_Error;
+//        interference_Error = ars408_can_database_ch5_rx.RadarState_ch5.RadarState_Interference;
+//        temperature_Error = ars408_can_database_ch5_rx.RadarState_ch5.RadarState_Temperature_Error;
+//        temporary_Error = ars408_can_database_ch5_rx.RadarState_ch5.RadarState_Temporary_Error;
+//        voltage_Error = ars408_can_database_ch5_rx.RadarState_ch5.RadarState_Voltage_Error;
+//        speed_Loss = ars408_can_database_ch5_rx.RadarState_ch5.RadarState_MotionRxState & 0x01;
+//        yaw_Rate_Loss = (ars408_can_database_ch5_rx.RadarState_ch5.RadarState_MotionRxState >> 1) & 0x01;
+//        break;
+//    case 0x700:
+//        major = std::to_string((unsigned int)ars408_can_database_ch5_rx.VersionID_ch5.Version_MajorRelease);
+//        minor = std::to_string((unsigned int)ars408_can_database_ch5_rx.VersionID_ch5.Version_MinorRelease);
+//        patch = std::to_string((unsigned int)ars408_can_database_ch5_rx.VersionID_ch5.Version_PatchLevel);
+//        radar_Version = major + "." + minor + "." + patch;
+//        break;
+//    case 0x60A:
+//        if(ars408_can_database_ch5_rx.Obj_0_Status_ch5.Obj_NofObjects == 0)
+//        {
+//            xradarObjArray.Clear();
+//            xradarObjArray.set_mstime(QDateTime::currentMSecsSinceEpoch());
+//            xradarObjArray.set_persistent_error(persistent_Error);
+//            xradarObjArray.set_interference_error(interference_Error);
+//            xradarObjArray.set_temperature_error(temperature_Error);
+//            xradarObjArray.set_temporary_error(temporary_Error);
+//            xradarObjArray.set_voltage_error(voltage_Error);
+//            xradarObjArray.set_speed_loss(speed_Loss);
+//            xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
+//            xradarObjArray.set_radar_version(radar_Version);
+
+//            radarObjArraySend_lock.lock();
+//            radarObjArray_send.CopyFrom(xradarObjArray);
+//            radarObjArraySend_lock.unlock();
+//            emit RadarObjectArray_Ready();
+//        }
+//        else
+//        {
+//            xradarObjArray.Clear();
+//            for(int i=0;i<RADAR_OBJ_MAX_NUM;i++)
+//            {
+//                if(radarObjFreshFlag[i] == true)
+//                {
+//                    pobj = xradarObjArray.add_obj();
+//                    pobj->CopyFrom(vradarObj[i]);
+//                }
+//            }
+//            xradarObjArray.set_mstime(QDateTime::currentMSecsSinceEpoch());
+//            xradarObjArray.set_persistent_error(persistent_Error);
+//            xradarObjArray.set_interference_error(interference_Error);
+//            xradarObjArray.set_temperature_error(temperature_Error);
+//            xradarObjArray.set_temporary_error(temporary_Error);
+//            xradarObjArray.set_voltage_error(voltage_Error);
+//            xradarObjArray.set_speed_loss(speed_Loss);
+//            xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
+//            xradarObjArray.set_radar_version(radar_Version);
+
+//            radarObjArraySend_lock.lock();
+//            radarObjArray_send.CopyFrom(xradarObjArray);
+//            radarObjArraySend_lock.unlock();
+////            std::cout<<radarObjArray_send.obj_size()<<std::endl;
+//            emit RadarObjectArray_Ready();
+//        }
+//        //clear the obj vector and flag vector
+//        vradarObj.fill(xradarObj_null,RADAR_OBJ_MAX_NUM);
+//        radarObjFreshFlag.fill(false,RADAR_OBJ_MAX_NUM);
+//        break;
+//    case 0x60B:
+//        tempObjID = ars408_can_database_ch5_rx.Obj_1_General_ch5.Obj_ID;
+//        radarObjFreshFlag[tempObjID] = true;
+//        tempDX = -ars408_can_database_ch5_rx.Obj_1_General_ch5.Obj_DistLat_phys;
+//        tempDY = ars408_can_database_ch5_rx.Obj_1_General_ch5.Obj_DistLong_phys;
+//        this->Rotate_Translate(tempDX,tempDY,setupConfig.radarAzimuth,setupConfig.radarOffsetX,setupConfig.radarOffsetY);
+//        vradarObj[tempObjID].set_x(tempDX);
+//        vradarObj[tempObjID].set_y(tempDY);
+//        tempVX = -ars408_can_database_ch5_rx.Obj_1_General_ch5.Obj_VrelLat_phys;
+//        tempVY = ars408_can_database_ch5_rx.Obj_1_General_ch5.Obj_VrelLong_phys;
+//        this->Rotate_Translate(tempVX,tempVY,setupConfig.radarAzimuth,setupConfig.radarOffsetX,setupConfig.radarOffsetY);
+//        vradarObj[tempObjID].set_vx(tempVX);
+//        vradarObj[tempObjID].set_vy(tempVY);
+//        vradarObj[tempObjID].set_vel(sqrt(tempVX*tempVX+tempVY*tempVY));
+//        vradarObj[tempObjID].set_bvalid(true);
+//        vradarObj[tempObjID].set_id(tempObjID);
+//        vradarObj[tempObjID].set_dynamic_property(ars408_can_database_ch5_rx.Obj_1_General_ch5.Obj_DynProp);
+//        vradarObj[tempObjID].set_rcs_radarcrosssection(ars408_can_database_ch5_rx.Obj_1_General_ch5.Obj_RCS_phys);
+//        break;
+//    case 0x60C:
+//        tempObjID = ars408_can_database_ch5_rx.Obj_2_Quality_ch5.Obj_ID;
+//        vradarObj[tempObjID].set_distlong_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch5_rx.Obj_2_Quality_ch5.Obj_DistLong_rms));
+//        vradarObj[tempObjID].set_distlat_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch5_rx.Obj_2_Quality_ch5.Obj_DistLat_rms));
+//        vradarObj[tempObjID].set_vrellong_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch5_rx.Obj_2_Quality_ch5.Obj_VrelLong_rms));
+//        vradarObj[tempObjID].set_vrellat_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch5_rx.Obj_2_Quality_ch5.Obj_VrelLat_rms));
+//        vradarObj[tempObjID].set_object_arellatrms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch5_rx.Obj_2_Quality_ch5.Obj_ArelLat_rms));
+//        vradarObj[tempObjID].set_object_arellongrms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch5_rx.Obj_2_Quality_ch5.Obj_ArelLong_rms));
+//        vradarObj[tempObjID].set_object_orientationrms(this->Trans_Ori_RMS_Ro_To_Phy(ars408_can_database_ch5_rx.Obj_2_Quality_ch5.Obj_Orientation_rms));
+//        vradarObj[tempObjID].set_object_measurestate(ars408_can_database_ch5_rx.Obj_2_Quality_ch5.Obj_MeasState);
+//        vradarObj[tempObjID].set_object_probofexist(this->Trans_ProbOfExist_Ro_To_Phy(ars408_can_database_ch5_rx.Obj_2_Quality_ch5.Obj_ProbOfExist));
+//        break;
+//    case 0x60D:
+//        tempObjID = ars408_can_database_ch5_rx.Obj_3_Extended_ch5.Obj_ID;
+//        tempAX = -ars408_can_database_ch5_rx.Obj_3_Extended_ch5.Obj_ArelLat_phys;
+//        tempAY = ars408_can_database_ch5_rx.Obj_3_Extended_ch5.Obj_ArelLong_phys;
+//        this->Rotate_Translate(tempAX,tempAY,setupConfig.radarAzimuth,setupConfig.radarOffsetX,setupConfig.radarOffsetY);
+//        vradarObj[tempObjID].set_object_arellong(tempAY);
+//        vradarObj[tempObjID].set_object_arellat(tempAX);
+//        tempOri = ars408_can_database_ch5_rx.Obj_3_Extended_ch5.Obj_OrientationAngle_phys + setupConfig.radarAzimuth;
+//        if(tempOri > 180.0)tempOri = tempOri - 360.0;
+//        if(tempOri < -180.0)tempOri = tempOri + 360.0;
+//        vradarObj[tempObjID].set_object_orientationangle(tempOri);
+//        vradarObj[tempObjID].set_object_class(ars408_can_database_ch5_rx.Obj_3_Extended_ch5.Obj_Class);
+//        vradarObj[tempObjID].set_object_length(ars408_can_database_ch5_rx.Obj_3_Extended_ch5.Obj_Length_phys);
+//        vradarObj[tempObjID].set_object_width(ars408_can_database_ch5_rx.Obj_3_Extended_ch5.Obj_Width_phys);
+//        break;
+//    default:
+//        break;
+//    }
+//}
+
+//void CANRecv_Consumer::Pack_Info_To_SHM_ch6(uint32_t can_id)
+//{
+//    std::string major,minor,patch;
+//    iv::radar::radarobject *pobj;
+//    iv::radar::radarobject xradarObj_null;
+//    double tempDX,tempDY,tempVX,tempVY,tempAX,tempAY,tempOri;
+//    uint8_t tempObjID;
+
+//    switch (can_id - 0x060) {
+//    case 0x201:
+//        persistent_Error = ars408_can_database_ch6_rx.RadarState_ch6.RadarState_Persistent_Error;
+//        interference_Error = ars408_can_database_ch6_rx.RadarState_ch6.RadarState_Interference;
+//        temperature_Error = ars408_can_database_ch6_rx.RadarState_ch6.RadarState_Temperature_Error;
+//        temporary_Error = ars408_can_database_ch6_rx.RadarState_ch6.RadarState_Temporary_Error;
+//        voltage_Error = ars408_can_database_ch6_rx.RadarState_ch6.RadarState_Voltage_Error;
+//        speed_Loss = ars408_can_database_ch6_rx.RadarState_ch6.RadarState_MotionRxState & 0x01;
+//        yaw_Rate_Loss = (ars408_can_database_ch6_rx.RadarState_ch6.RadarState_MotionRxState >> 1) & 0x01;
+//        break;
+//    case 0x700:
+//        major = std::to_string((unsigned int)ars408_can_database_ch6_rx.VersionID_ch6.Version_MajorRelease);
+//        minor = std::to_string((unsigned int)ars408_can_database_ch6_rx.VersionID_ch6.Version_MinorRelease);
+//        patch = std::to_string((unsigned int)ars408_can_database_ch6_rx.VersionID_ch6.Version_PatchLevel);
+//        radar_Version = major + "." + minor + "." + patch;
+//        break;
+//    case 0x60A:
+//        if(ars408_can_database_ch6_rx.Obj_0_Status_ch6.Obj_NofObjects == 0)
+//        {
+//            xradarObjArray.Clear();
+//            xradarObjArray.set_mstime(QDateTime::currentMSecsSinceEpoch());
+//            xradarObjArray.set_persistent_error(persistent_Error);
+//            xradarObjArray.set_interference_error(interference_Error);
+//            xradarObjArray.set_temperature_error(temperature_Error);
+//            xradarObjArray.set_temporary_error(temporary_Error);
+//            xradarObjArray.set_voltage_error(voltage_Error);
+//            xradarObjArray.set_speed_loss(speed_Loss);
+//            xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
+//            xradarObjArray.set_radar_version(radar_Version);
+
+//            radarObjArraySend_lock.lock();
+//            radarObjArray_send.CopyFrom(xradarObjArray);
+//            radarObjArraySend_lock.unlock();
+//            emit RadarObjectArray_Ready();
+//        }
+//        else
+//        {
+//            xradarObjArray.Clear();
+//            for(int i=0;i<RADAR_OBJ_MAX_NUM;i++)
+//            {
+//                if(radarObjFreshFlag[i] == true)
+//                {
+//                    pobj = xradarObjArray.add_obj();
+//                    pobj->CopyFrom(vradarObj[i]);
+//                }
+//            }
+//            xradarObjArray.set_mstime(QDateTime::currentMSecsSinceEpoch());
+//            xradarObjArray.set_persistent_error(persistent_Error);
+//            xradarObjArray.set_interference_error(interference_Error);
+//            xradarObjArray.set_temperature_error(temperature_Error);
+//            xradarObjArray.set_temporary_error(temporary_Error);
+//            xradarObjArray.set_voltage_error(voltage_Error);
+//            xradarObjArray.set_speed_loss(speed_Loss);
+//            xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
+//            xradarObjArray.set_radar_version(radar_Version);
+
+//            radarObjArraySend_lock.lock();
+//            radarObjArray_send.CopyFrom(xradarObjArray);
+//            radarObjArraySend_lock.unlock();
+////            std::cout<<radarObjArray_send.obj_size()<<std::endl;
+//            emit RadarObjectArray_Ready();
+//        }
+//        //clear the obj vector and flag vector
+//        vradarObj.fill(xradarObj_null,RADAR_OBJ_MAX_NUM);
+//        radarObjFreshFlag.fill(false,RADAR_OBJ_MAX_NUM);
+//        break;
+//    case 0x60B:
+//        tempObjID = ars408_can_database_ch6_rx.Obj_1_General_ch6.Obj_ID;
+//        radarObjFreshFlag[tempObjID] = true;
+//        tempDX = -ars408_can_database_ch6_rx.Obj_1_General_ch6.Obj_DistLat_phys;
+//        tempDY = ars408_can_database_ch6_rx.Obj_1_General_ch6.Obj_DistLong_phys;
+//        this->Rotate_Translate(tempDX,tempDY,setupConfig.radarAzimuth,setupConfig.radarOffsetX,setupConfig.radarOffsetY);
+//        vradarObj[tempObjID].set_x(tempDX);
+//        vradarObj[tempObjID].set_y(tempDY);
+//        tempVX = -ars408_can_database_ch6_rx.Obj_1_General_ch6.Obj_VrelLat_phys;
+//        tempVY = ars408_can_database_ch6_rx.Obj_1_General_ch6.Obj_VrelLong_phys;
+//        this->Rotate_Translate(tempVX,tempVY,setupConfig.radarAzimuth,setupConfig.radarOffsetX,setupConfig.radarOffsetY);
+//        vradarObj[tempObjID].set_vx(tempVX);
+//        vradarObj[tempObjID].set_vy(tempVY);
+//        vradarObj[tempObjID].set_vel(sqrt(tempVX*tempVX+tempVY*tempVY));
+//        vradarObj[tempObjID].set_bvalid(true);
+//        vradarObj[tempObjID].set_id(tempObjID);
+//        vradarObj[tempObjID].set_dynamic_property(ars408_can_database_ch6_rx.Obj_1_General_ch6.Obj_DynProp);
+//        vradarObj[tempObjID].set_rcs_radarcrosssection(ars408_can_database_ch6_rx.Obj_1_General_ch6.Obj_RCS_phys);
+//        break;
+//    case 0x60C:
+//        tempObjID = ars408_can_database_ch6_rx.Obj_2_Quality_ch6.Obj_ID;
+//        vradarObj[tempObjID].set_distlong_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch6_rx.Obj_2_Quality_ch6.Obj_DistLong_rms));
+//        vradarObj[tempObjID].set_distlat_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch6_rx.Obj_2_Quality_ch6.Obj_DistLat_rms));
+//        vradarObj[tempObjID].set_vrellong_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch6_rx.Obj_2_Quality_ch6.Obj_VrelLong_rms));
+//        vradarObj[tempObjID].set_vrellat_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch6_rx.Obj_2_Quality_ch6.Obj_VrelLat_rms));
+//        vradarObj[tempObjID].set_object_arellatrms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch6_rx.Obj_2_Quality_ch6.Obj_ArelLat_rms));
+//        vradarObj[tempObjID].set_object_arellongrms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch6_rx.Obj_2_Quality_ch6.Obj_ArelLong_rms));
+//        vradarObj[tempObjID].set_object_orientationrms(this->Trans_Ori_RMS_Ro_To_Phy(ars408_can_database_ch6_rx.Obj_2_Quality_ch6.Obj_Orientation_rms));
+//        vradarObj[tempObjID].set_object_measurestate(ars408_can_database_ch6_rx.Obj_2_Quality_ch6.Obj_MeasState);
+//        vradarObj[tempObjID].set_object_probofexist(this->Trans_ProbOfExist_Ro_To_Phy(ars408_can_database_ch6_rx.Obj_2_Quality_ch6.Obj_ProbOfExist));
+//        break;
+//    case 0x60D:
+//        tempObjID = ars408_can_database_ch6_rx.Obj_3_Extended_ch6.Obj_ID;
+//        tempAX = -ars408_can_database_ch6_rx.Obj_3_Extended_ch6.Obj_ArelLat_phys;
+//        tempAY = ars408_can_database_ch6_rx.Obj_3_Extended_ch6.Obj_ArelLong_phys;
+//        this->Rotate_Translate(tempAX,tempAY,setupConfig.radarAzimuth,setupConfig.radarOffsetX,setupConfig.radarOffsetY);
+//        vradarObj[tempObjID].set_object_arellong(tempAY);
+//        vradarObj[tempObjID].set_object_arellat(tempAX);
+//        tempOri = ars408_can_database_ch6_rx.Obj_3_Extended_ch6.Obj_OrientationAngle_phys + setupConfig.radarAzimuth;
+//        if(tempOri > 180.0)tempOri = tempOri - 360.0;
+//        if(tempOri < -180.0)tempOri = tempOri + 360.0;
+//        vradarObj[tempObjID].set_object_orientationangle(tempOri);
+//        vradarObj[tempObjID].set_object_class(ars408_can_database_ch6_rx.Obj_3_Extended_ch6.Obj_Class);
+//        vradarObj[tempObjID].set_object_length(ars408_can_database_ch6_rx.Obj_3_Extended_ch6.Obj_Length_phys);
+//        vradarObj[tempObjID].set_object_width(ars408_can_database_ch6_rx.Obj_3_Extended_ch6.Obj_Width_phys);
+//        break;
+//    default:
+//        break;
+//    }
+//}
+
+//void CANRecv_Consumer::Pack_Info_To_SHM_ch7(uint32_t can_id)
+//{
+//    std::string major,minor,patch;
+//    iv::radar::radarobject *pobj;
+//    iv::radar::radarobject xradarObj_null;
+//    double tempDX,tempDY,tempVX,tempVY,tempAX,tempAY,tempOri;
+//    uint8_t tempObjID;
+
+//    switch (can_id - 0x070) {
+//    case 0x201:
+//        persistent_Error = ars408_can_database_ch7_rx.RadarState_ch7.RadarState_Persistent_Error;
+//        interference_Error = ars408_can_database_ch7_rx.RadarState_ch7.RadarState_Interference;
+//        temperature_Error = ars408_can_database_ch7_rx.RadarState_ch7.RadarState_Temperature_Error;
+//        temporary_Error = ars408_can_database_ch7_rx.RadarState_ch7.RadarState_Temporary_Error;
+//        voltage_Error = ars408_can_database_ch7_rx.RadarState_ch7.RadarState_Voltage_Error;
+//        speed_Loss = ars408_can_database_ch7_rx.RadarState_ch7.RadarState_MotionRxState & 0x01;
+//        yaw_Rate_Loss = (ars408_can_database_ch7_rx.RadarState_ch7.RadarState_MotionRxState >> 1) & 0x01;
+//        break;
+//    case 0x700:
+//        major = std::to_string((unsigned int)ars408_can_database_ch7_rx.VersionID_ch7.Version_MajorRelease);
+//        minor = std::to_string((unsigned int)ars408_can_database_ch7_rx.VersionID_ch7.Version_MinorRelease);
+//        patch = std::to_string((unsigned int)ars408_can_database_ch7_rx.VersionID_ch7.Version_PatchLevel);
+//        radar_Version = major + "." + minor + "." + patch;
+//        break;
+//    case 0x60A:
+//        if(ars408_can_database_ch7_rx.Obj_0_Status_ch7.Obj_NofObjects == 0)
+//        {
+//            xradarObjArray.Clear();
+//            xradarObjArray.set_mstime(QDateTime::currentMSecsSinceEpoch());
+//            xradarObjArray.set_persistent_error(persistent_Error);
+//            xradarObjArray.set_interference_error(interference_Error);
+//            xradarObjArray.set_temperature_error(temperature_Error);
+//            xradarObjArray.set_temporary_error(temporary_Error);
+//            xradarObjArray.set_voltage_error(voltage_Error);
+//            xradarObjArray.set_speed_loss(speed_Loss);
+//            xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
+//            xradarObjArray.set_radar_version(radar_Version);
+
+//            radarObjArraySend_lock.lock();
+//            radarObjArray_send.CopyFrom(xradarObjArray);
+//            radarObjArraySend_lock.unlock();
+//            emit RadarObjectArray_Ready();
+//        }
+//        else
+//        {
+//            xradarObjArray.Clear();
+//            for(int i=0;i<RADAR_OBJ_MAX_NUM;i++)
+//            {
+//                if(radarObjFreshFlag[i] == true)
+//                {
+//                    pobj = xradarObjArray.add_obj();
+//                    pobj->CopyFrom(vradarObj[i]);
+//                }
+//            }
+//            xradarObjArray.set_mstime(QDateTime::currentMSecsSinceEpoch());
+//            xradarObjArray.set_persistent_error(persistent_Error);
+//            xradarObjArray.set_interference_error(interference_Error);
+//            xradarObjArray.set_temperature_error(temperature_Error);
+//            xradarObjArray.set_temporary_error(temporary_Error);
+//            xradarObjArray.set_voltage_error(voltage_Error);
+//            xradarObjArray.set_speed_loss(speed_Loss);
+//            xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
+//            xradarObjArray.set_radar_version(radar_Version);
+
+//            radarObjArraySend_lock.lock();
+//            radarObjArray_send.CopyFrom(xradarObjArray);
+//            radarObjArraySend_lock.unlock();
+////            std::cout<<radarObjArray_send.obj_size()<<std::endl;
+//            emit RadarObjectArray_Ready();
+//        }
+//        //clear the obj vector and flag vector
+//        vradarObj.fill(xradarObj_null,RADAR_OBJ_MAX_NUM);
+//        radarObjFreshFlag.fill(false,RADAR_OBJ_MAX_NUM);
+//        break;
+//    case 0x60B:
+//        tempObjID = ars408_can_database_ch7_rx.Obj_1_General_ch7.Obj_ID;
+//        radarObjFreshFlag[tempObjID] = true;
+//        tempDX = -ars408_can_database_ch7_rx.Obj_1_General_ch7.Obj_DistLat_phys;
+//        tempDY = ars408_can_database_ch7_rx.Obj_1_General_ch7.Obj_DistLong_phys;
+//        this->Rotate_Translate(tempDX,tempDY,setupConfig.radarAzimuth,setupConfig.radarOffsetX,setupConfig.radarOffsetY);
+//        vradarObj[tempObjID].set_x(tempDX);
+//        vradarObj[tempObjID].set_y(tempDY);
+//        tempVX = -ars408_can_database_ch7_rx.Obj_1_General_ch7.Obj_VrelLat_phys;
+//        tempVY = ars408_can_database_ch7_rx.Obj_1_General_ch7.Obj_VrelLong_phys;
+//        this->Rotate_Translate(tempVX,tempVY,setupConfig.radarAzimuth,setupConfig.radarOffsetX,setupConfig.radarOffsetY);
+//        vradarObj[tempObjID].set_vx(tempVX);
+//        vradarObj[tempObjID].set_vy(tempVY);
+//        vradarObj[tempObjID].set_vel(sqrt(tempVX*tempVX+tempVY*tempVY));
+//        vradarObj[tempObjID].set_bvalid(true);
+//        vradarObj[tempObjID].set_id(tempObjID);
+//        vradarObj[tempObjID].set_dynamic_property(ars408_can_database_ch7_rx.Obj_1_General_ch7.Obj_DynProp);
+//        vradarObj[tempObjID].set_rcs_radarcrosssection(ars408_can_database_ch7_rx.Obj_1_General_ch7.Obj_RCS_phys);
+//        break;
+//    case 0x60C:
+//        tempObjID = ars408_can_database_ch7_rx.Obj_2_Quality_ch7.Obj_ID;
+//        vradarObj[tempObjID].set_distlong_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch7_rx.Obj_2_Quality_ch7.Obj_DistLong_rms));
+//        vradarObj[tempObjID].set_distlat_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch7_rx.Obj_2_Quality_ch7.Obj_DistLat_rms));
+//        vradarObj[tempObjID].set_vrellong_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch7_rx.Obj_2_Quality_ch7.Obj_VrelLong_rms));
+//        vradarObj[tempObjID].set_vrellat_rms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch7_rx.Obj_2_Quality_ch7.Obj_VrelLat_rms));
+//        vradarObj[tempObjID].set_object_arellatrms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch7_rx.Obj_2_Quality_ch7.Obj_ArelLat_rms));
+//        vradarObj[tempObjID].set_object_arellongrms(this->Trans_DVA_RMS_Ro_To_Phy(ars408_can_database_ch7_rx.Obj_2_Quality_ch7.Obj_ArelLong_rms));
+//        vradarObj[tempObjID].set_object_orientationrms(this->Trans_Ori_RMS_Ro_To_Phy(ars408_can_database_ch7_rx.Obj_2_Quality_ch7.Obj_Orientation_rms));
+//        vradarObj[tempObjID].set_object_measurestate(ars408_can_database_ch7_rx.Obj_2_Quality_ch7.Obj_MeasState);
+//        vradarObj[tempObjID].set_object_probofexist(this->Trans_ProbOfExist_Ro_To_Phy(ars408_can_database_ch7_rx.Obj_2_Quality_ch7.Obj_ProbOfExist));
+//        break;
+//    case 0x60D:
+//        tempObjID = ars408_can_database_ch7_rx.Obj_3_Extended_ch7.Obj_ID;
+//        tempAX = -ars408_can_database_ch7_rx.Obj_3_Extended_ch7.Obj_ArelLat_phys;
+//        tempAY = ars408_can_database_ch7_rx.Obj_3_Extended_ch7.Obj_ArelLong_phys;
+//        this->Rotate_Translate(tempAX,tempAY,setupConfig.radarAzimuth,setupConfig.radarOffsetX,setupConfig.radarOffsetY);
+//        vradarObj[tempObjID].set_object_arellong(tempAY);
+//        vradarObj[tempObjID].set_object_arellat(tempAX);
+//        tempOri = ars408_can_database_ch7_rx.Obj_3_Extended_ch7.Obj_OrientationAngle_phys + setupConfig.radarAzimuth;
+//        if(tempOri > 180.0)tempOri = tempOri - 360.0;
+//        if(tempOri < -180.0)tempOri = tempOri + 360.0;
+//        vradarObj[tempObjID].set_object_orientationangle(tempOri);
+//        vradarObj[tempObjID].set_object_class(ars408_can_database_ch7_rx.Obj_3_Extended_ch7.Obj_Class);
+//        vradarObj[tempObjID].set_object_length(ars408_can_database_ch7_rx.Obj_3_Extended_ch7.Obj_Length_phys);
+//        vradarObj[tempObjID].set_object_width(ars408_can_database_ch7_rx.Obj_3_Extended_ch7.Obj_Width_phys);
+//        break;
+//    default:
+//        break;
+//    }
+//}
+
+//double CANRecv_Consumer::Trans_DVA_RMS_Ro_To_Phy(uint8_t data)
+//{
+//    double phy;
+//    switch (data) {
+//    case 0x0: phy = 0.005;break;
+//    case 0x1: phy = 0.006;break;
+//    case 0x2: phy = 0.008;break;
+//    case 0x3: phy = 0.011;break;
+//    case 0x4: phy = 0.014;break;
+//    case 0x5: phy = 0.018;break;
+//    case 0x6: phy = 0.023;break;
+//    case 0x7: phy = 0.029;break;
+//    case 0x8: phy = 0.038;break;
+//    case 0x9: phy = 0.049;break;
+//    case 0xA: phy = 0.063;break;
+//    case 0xB: phy = 0.081;break;
+//    case 0xC: phy = 0.105;break;
+//    case 0xD: phy = 0.135;break;
+//    case 0xE: phy = 0.174;break;
+//    case 0xF: phy = 0.224;break;
+//    case 0x10: phy = 0.288;break;
+//    case 0x11: phy = 0.371;break;
+//    case 0x12: phy = 0.478;break;
+//    case 0x13: phy = 0.616;break;
+//    case 0x14: phy = 0.794;break;
+//    case 0x15: phy = 1.023;break;
+//    case 0x16: phy = 1.317;break;
+//    case 0x17: phy = 1.697;break;
+//    case 0x18: phy = 2.187;break;
+//    case 0x19: phy = 2.817;break;
+//    case 0x1A: phy = 3.630;break;
+//    case 0x1B: phy = 4.676;break;
+//    case 0x1C: phy = 6.025;break;
+//    case 0x1D: phy = 7.762;break;
+//    case 0x1E: phy = 10.000;break;
+//    case 0x1F: phy = -1.0;break;
+//    default:
+//        phy =  -1.0;
+//        break;
+//    }
+
+//    return phy;
+//}
+
+//double CANRecv_Consumer::Trans_Ori_RMS_Ro_To_Phy(uint8_t data)
+//{
+//    double phy;
+//    switch (data) {
+//    case 0x0: phy = 0.005;break;
+//    case 0x1: phy = 0.007;break;
+//    case 0x2: phy = 0.010;break;
+//    case 0x3: phy = 0.014;break;
+//    case 0x4: phy = 0.020;break;
+//    case 0x5: phy = 0.029;break;
+//    case 0x6: phy = 0.041;break;
+//    case 0x7: phy = 0.058;break;
+//    case 0x8: phy = 0.082;break;
+//    case 0x9: phy = 0.116;break;
+//    case 0xA: phy = 0.165;break;
+//    case 0xB: phy = 0.234;break;
+//    case 0xC: phy = 0.332;break;
+//    case 0xD: phy = 0.471;break;
+//    case 0xE: phy = 0.669;break;
+//    case 0xF: phy = 0.949;break;
+//    case 0x10: phy = 1.346;break;
+//    case 0x11: phy = 1.909;break;
+//    case 0x12: phy = 2.709;break;
+//    case 0x13: phy = 3.843;break;
+//    case 0x14: phy = 5.451;break;
+//    case 0x15: phy = 7.734;break;
+//    case 0x16: phy = 10.971;break;
+//    case 0x17: phy = 15.565;break;
+//    case 0x18: phy = 22.081;break;
+//    case 0x19: phy = 31.325;break;
+//    case 0x1A: phy = 44.439;break;
+//    case 0x1B: phy = 63.044;break;
+//    case 0x1C: phy = 89.437;break;
+//    case 0x1D: phy = 126.881;break;
+//    case 0x1E: phy = 180.000;break;
+//    case 0x1F: phy = -1.0;break;
+//    default:
+//        phy =  -1.0;
+//        break;
+//    }
+
+//    return phy;
+//}
+
+//double CANRecv_Consumer::Trans_ProbOfExist_Ro_To_Phy(uint8_t data)
+//{
+//    double phy;
+//    switch (data) {
+//    case 0x0:
+//        phy = -1.0;
+//        break;
+//    case 0x1:
+//        phy = 25.0;
+//        break;
+//    case 0x2:
+//        phy = 50.0;
+//        break;
+//    case 0x3:
+//        phy = 75.0;
+//        break;
+//    case 0x4:
+//        phy = 90.0;
+//        break;
+//    case 0x5:
+//        phy = 99.0;
+//        break;
+//    case 0x6:
+//        phy = 99.9;
+//        break;
+//    case 0x7:
+//        phy = 100.0;
+//        break;
+//    default:
+//        phy = 0.0;
+//        break;
+//    }
+
+//    return phy;
+//}
+
+//void CANRecv_Consumer::Rotate_Translate(double &x,double &y,double theta,double offset_x,double offset_y) //RFU,deg
+//{
+//    double tempX = x;
+//    double tempY = y;
+//    double tempTheta = theta / 180.0 * M_PI;
+//    double tempSinTheta = sin(tempTheta);
+//    double tempCosTheta = cos(tempTheta);
+
+//    x = (tempX * tempCosTheta + tempY * tempSinTheta) + offset_x;
+//    y = (tempY * tempCosTheta - tempX * tempSinTheta) + offset_y;
+//}
+
+//void CANRecv_Consumer::run()
+//{
+//    radarType = setupConfig.radarType;
+
+//    uint32_t tempCANID = 0x000u;
+
+//    while (!QThread::isInterruptionRequested())
+//    {
+//        switch (setupConfig.radarID) {
+//        case 0:
+//            this->Trans_From_CANRaw(pBuffer->Consume_Element());
+//            tempCANID = ars408_can_database_ch0_Receive(&ars408_can_database_ch0_rx,CAN_data,CAN_ID,CAN_DLC);
+//            Pack_Info_To_SHM_ch0(tempCANID);
+//            break;
+//        case 1:
+//            this->Trans_From_CANRaw(pBuffer->Consume_Element());
+//            tempCANID = ars408_can_database_ch1_Receive(&ars408_can_database_ch1_rx,CAN_data,CAN_ID,CAN_DLC);
+//            Pack_Info_To_SHM_ch1(tempCANID);
+//            break;
+//        case 2:
+//            this->Trans_From_CANRaw(pBuffer->Consume_Element());
+//            tempCANID = ars408_can_database_ch2_Receive(&ars408_can_database_ch2_rx,CAN_data,CAN_ID,CAN_DLC);
+//            Pack_Info_To_SHM_ch2(tempCANID);
+//            break;
+//        case 3:
+//            this->Trans_From_CANRaw(pBuffer->Consume_Element());
+//            tempCANID = ars408_can_database_ch3_Receive(&ars408_can_database_ch3_rx,CAN_data,CAN_ID,CAN_DLC);
+//            Pack_Info_To_SHM_ch3(tempCANID);
+//            break;
+//        case 4:
+//            this->Trans_From_CANRaw(pBuffer->Consume_Element());
+//            tempCANID = ars408_can_database_ch4_Receive(&ars408_can_database_ch4_rx,CAN_data,CAN_ID,CAN_DLC);
+//            Pack_Info_To_SHM_ch4(tempCANID);
+//            break;
+//        case 5:
+//            this->Trans_From_CANRaw(pBuffer->Consume_Element());
+//            tempCANID = ars408_can_database_ch5_Receive(&ars408_can_database_ch5_rx,CAN_data,CAN_ID,CAN_DLC);
+//            Pack_Info_To_SHM_ch5(tempCANID);
+//            break;
+//        case 6:
+//            this->Trans_From_CANRaw(pBuffer->Consume_Element());
+//            tempCANID = ars408_can_database_ch6_Receive(&ars408_can_database_ch6_rx,CAN_data,CAN_ID,CAN_DLC);
+//            Pack_Info_To_SHM_ch6(tempCANID);
+//            break;
+//        case 7:
+//            this->Trans_From_CANRaw(pBuffer->Consume_Element());
+//            tempCANID = ars408_can_database_ch7_Receive(&ars408_can_database_ch7_rx,CAN_data,CAN_ID,CAN_DLC);
+//            Pack_Info_To_SHM_ch7(tempCANID);
+//            break;
+//        default:
+//            break;
+//        }
+//    }
+//}
+
+//void CANRecv_Consumer::RadarObjectArray_Ready_Slot()
+//{
+//    radarObjArraySend_lock.lock();
+//    int ndatasize = radarObjArray_send.ByteSize();
+//    char * strser = new char[ndatasize];
+//    std::shared_ptr<char> pstrser;
+//    pstrser.reset(strser);
+//    if(radarObjArray_send.SerializePartialToArray(strser,ndatasize))
+//    {
+//        iv::modulecomm::ModuleSendMsg(shmSonar.mpa,strser,ndatasize);
+//    }
+//    else
+//    {
+//        std::cout<<"RadarObjectArray serialize error."<<std::endl;
+//    }
+//    radarObjArraySend_lock.unlock();
+//}

+ 85 - 0
src/driver/driver_ultrasonic_dauxi_KS136A/canrecv_consumer.h

@@ -0,0 +1,85 @@
+#ifndef CANRECV_CONSUMER_H
+#define CANRECV_CONSUMER_H
+
+//#include <QObject>
+//#include <QTimer>
+//#include <QDateTime>
+//#include <QThread>
+
+//#include "modulecomm.h"
+//#include "radarobjectarray.pb.h"
+
+//#include "can_producer_consumer.h"
+//#include "decode_cfg.h"
+//#include "iv_msgunit.h"
+
+//#define RADAR_OBJ_MAX_NUM 128
+
+//class CANRecv_Consumer : public QThread
+//{
+//    Q_OBJECT
+//public:
+//    CANRecv_Consumer(CAN_Producer_Consumer *pBuf);
+//    ~CANRecv_Consumer();
+//    void Clear_CAN_PrivateTempVariable(void);
+
+//protected:
+//    void run();
+//    uint32_t Trans_From_CANRaw(const iv::can::canraw &xraw); //only for standard data frame, return can id
+//    void Pack_Info_To_SHM_ch0(uint32_t can_id);
+//    void Pack_Info_To_SHM_ch1(uint32_t can_id);
+//    void Pack_Info_To_SHM_ch2(uint32_t can_id);
+//    void Pack_Info_To_SHM_ch3(uint32_t can_id);
+//    void Pack_Info_To_SHM_ch4(uint32_t can_id);
+//    void Pack_Info_To_SHM_ch5(uint32_t can_id);
+//    void Pack_Info_To_SHM_ch6(uint32_t can_id);
+//    void Pack_Info_To_SHM_ch7(uint32_t can_id);
+//    //ro trans phy 3
+//    double Trans_DVA_RMS_Ro_To_Phy(uint8_t data);
+//    double Trans_Ori_RMS_Ro_To_Phy(uint8_t data);
+//    double Trans_ProbOfExist_Ro_To_Phy(uint8_t data);
+//    //rotation and translation
+//    void Rotate_Translate(double &x,double &y,double theta,double offset_x,double offset_y); //RFU,deg
+
+//signals:
+//    void RadarObjectArray_Ready();
+
+//private slots:
+//    void RadarObjectArray_Ready_Slot();
+
+//private:
+//    CAN_Producer_Consumer *pBuffer;
+
+//    uint8_t radarType = 0; //0 ARS408-21xx 1 ARS408-21sc3 2 SRR308
+
+//    uint32_t CAN_ID = 0x000u;
+//    uint8_t CAN_DLC = 0;
+//    uint8_t CAN_data[8] = {0};
+
+//    ars408_can_database_ch0_rx_t ars408_can_database_ch0_rx;
+//    ars408_can_database_ch1_rx_t ars408_can_database_ch1_rx;
+//    ars408_can_database_ch2_rx_t ars408_can_database_ch2_rx;
+//    ars408_can_database_ch3_rx_t ars408_can_database_ch3_rx;
+//    ars408_can_database_ch4_rx_t ars408_can_database_ch4_rx;
+//    ars408_can_database_ch5_rx_t ars408_can_database_ch5_rx;
+//    ars408_can_database_ch6_rx_t ars408_can_database_ch6_rx;
+//    ars408_can_database_ch7_rx_t ars408_can_database_ch7_rx;
+
+//    iv::radar::radarobjectarray xradarObjArray;
+//    QVector<iv::radar::radarobject> vradarObj;
+//    QVector<bool> radarObjFreshFlag;
+
+//    bool persistent_Error = false; //notice if multi thread, these param need a mutex lock
+//    bool interference_Error = false; //
+//    bool temperature_Error = false; //
+//    bool temporary_Error = false; //
+//    bool voltage_Error = false; //
+//    bool speed_Loss = false; //
+//    bool yaw_Rate_Loss = false; //
+//    std::string radar_Version = "4.30.1"; //
+
+//    iv::radar::radarobjectarray radarObjArray_send;
+//    QMutex radarObjArraySend_lock;
+//};
+
+#endif // CANRECV_CONSUMER_H

+ 71 - 0
src/driver/driver_ultrasonic_dauxi_KS136A/cansend_consumer.cpp

@@ -0,0 +1,71 @@
+#include "cansend_consumer.h"
+
+#include <thread>
+
+extern setupConfig_t setupConfig;
+extern iv::msgunit shmCANSend;
+
+CANSend_Consumer::CANSend_Consumer(CAN_Producer_Consumer *pBuf)
+{
+    pBuffer = pBuf;
+}
+
+CANSend_Consumer::~CANSend_Consumer()
+{
+    requestInterruption();
+    while(this->isFinished() == false);
+}
+
+void CANSend_Consumer::run()
+{
+    QTime xTime;
+    xTime.start();
+
+    int lastTime = xTime.elapsed();
+    uint64_t interval = 20; //interval time should more than 10 ms
+
+    uint64_t CANPackageIndex = 0;
+    uint8_t CANPackageChannel;
+    iv::can::canmsg xmsg;
+
+    if(setupConfig.strMemCANSend == "cansend0")
+        CANPackageChannel = 0;
+    else
+        CANPackageChannel = 1;
+
+    while (!QThread::isInterruptionRequested())
+    {
+        pBuffer->Consume_Element_To_CANMsg(xmsg); //this function is block mode
+
+        if(abs(xTime.elapsed() - lastTime)>=interval || xmsg.rawmsg_size() > 3500)
+        {
+            //update timer
+            lastTime = xTime.elapsed();
+            if(xmsg.rawmsg_size()>0) //actrully, because the fucntion before this is block mode, this determine is allways true, just for safety
+            {
+                //pack
+                xmsg.set_index(CANPackageIndex);
+                xmsg.set_channel(CANPackageChannel);
+                xmsg.set_mstime(QDateTime::currentMSecsSinceEpoch());
+                //send
+                int ndatasize = xmsg.ByteSize();
+                char * strser = new char[ndatasize];
+                std::shared_ptr<char> pstrser;
+                pstrser.reset(strser);
+                if(xmsg.SerializePartialToArray(strser,ndatasize))
+                {
+                    iv::modulecomm::ModuleSendMsg(shmCANSend.mpa,strser,ndatasize);
+                }
+                else
+                {
+                    std::cout<<"CANSend_Consumer serialize error."<<std::endl;
+                }
+                //clear and update index
+                xmsg.clear_rawmsg();
+                CANPackageIndex++;
+            }
+            else
+                std::cout << "rawmsg size is zero, no data need to be send." << std::endl;
+        }
+    }
+}

+ 29 - 0
src/driver/driver_ultrasonic_dauxi_KS136A/cansend_consumer.h

@@ -0,0 +1,29 @@
+#ifndef CANSEND_CONSUMER_H
+#define CANSEND_CONSUMER_H
+
+#include <QObject>
+#include <QTimer>
+#include <QDateTime>
+#include <QThread>
+
+#include "modulecomm.h"
+
+#include "can_producer_consumer.h"
+#include "decode_cfg.h"
+#include "iv_msgunit.h"
+
+class CANSend_Consumer : public QThread
+{
+    Q_OBJECT
+public:
+    CANSend_Consumer(CAN_Producer_Consumer *pBuf);
+    ~CANSend_Consumer();
+
+protected:
+    void run();
+
+private:
+    CAN_Producer_Consumer *pBuffer;
+};
+
+#endif // CANSEND_CONSUMER_H

+ 70 - 0
src/driver/driver_ultrasonic_dauxi_KS136A/cansend_producer.cpp

@@ -0,0 +1,70 @@
+#include "cansend_producer.h"
+
+#include "math.h"
+
+#include <thread>
+
+extern setupConfig_t setupConfig;
+
+CANSend_Producer::CANSend_Producer(CAN_Producer_Consumer *pBuf)
+{
+    pBuffer = pBuf;
+}
+
+CANSend_Producer::~CANSend_Producer()
+{
+    requestInterruption();
+    while(this->isFinished() == false);
+}
+
+void CANSend_Producer::Clear_CAN_PrivateTempVariable(void)
+{
+    CAN_ID = 0x000u;
+    CAN_IDE = 0;
+    CAN_RTR = 0;
+    CAN_DLC = 0;
+    for(int i=0;i<8;i++) CAN_data[i] = 0x00;
+}
+
+iv::can::canraw CANSend_Producer::Trans_to_CANRaw(void)
+{
+    iv::can::canraw xraw;
+    xraw.set_id(CAN_ID);
+    xraw.set_bext(CAN_IDE);
+    xraw.set_bremote(CAN_RTR);
+    xraw.set_len(CAN_DLC);
+    xraw.set_data(CAN_data,CAN_DLC);
+    xraw.set_rectime(QDateTime::currentMSecsSinceEpoch());
+
+    return xraw;
+}
+
+void CANSend_Producer::run()
+{
+    QTime xTime;
+    xTime.start();
+
+    int lastTime = xTime.elapsed();
+    uint64_t interval = 25; //interval time should more than 10 ms
+
+    while (!QThread::isInterruptionRequested())
+    {
+        if(abs(xTime.elapsed() - lastTime)>=interval)
+        {
+            //update timer
+            lastTime = xTime.elapsed();
+
+            this->Clear_CAN_PrivateTempVariable();
+            CAN_ID = setupConfig.sonarCAN_ID;
+            CAN_data[0] = 0xE8;
+            CAN_data[1] = 0x02;
+            CAN_data[2] = 0x16;
+            CAN_DLC = 3;
+            pBuffer->Produce_Element(this->Trans_to_CANRaw());
+        }
+        else
+        {
+            std::this_thread::sleep_for(std::chrono::microseconds(1000));//sleep 1ms
+        }
+    }
+}

+ 36 - 0
src/driver/driver_ultrasonic_dauxi_KS136A/cansend_producer.h

@@ -0,0 +1,36 @@
+#ifndef CANSEND_PRODUCER_H
+#define CANSEND_PRODUCER_H
+
+#include <QObject>
+#include <QTimer>
+#include <QDateTime>
+#include <QThread>
+
+#include "modulecomm.h"
+
+#include "can_producer_consumer.h"
+#include "decode_cfg.h"
+
+class CANSend_Producer : public QThread
+{
+    Q_OBJECT
+public:
+    CANSend_Producer(CAN_Producer_Consumer *pBuf);
+    ~CANSend_Producer();
+    void Clear_CAN_PrivateTempVariable(void);
+
+protected:
+    void run();
+    iv::can::canraw Trans_to_CANRaw(void);
+
+private:
+    CAN_Producer_Consumer *pBuffer;
+
+    uint32_t CAN_ID = 0x000u;
+    uint8_t CAN_IDE = 0;
+    uint8_t CAN_RTR = 0;
+    uint8_t CAN_DLC = 0;
+    uint8_t CAN_data[8] = {0};
+};
+
+#endif // CANSEND_PRODUCER_H

+ 17 - 0
src/driver/driver_ultrasonic_dauxi_KS136A/decode_cfg.cpp

@@ -0,0 +1,17 @@
+#include "decode_cfg.h"
+
+int DecodeSonarCfgFromXML(setupConfig_t &setupConfig , const std::string &xmlFilePath)
+{
+    iv::xmlparam::Xmlparam xp(xmlFilePath);
+
+    setupConfig.strMemCANRecv = xp.GetParam("canrecv_shm","canrecv0");
+    setupConfig.strMemCANSend = xp.GetParam("cansend_shm","cansend0");
+    setupConfig.strMemSonar = xp.GetParam("sonar_shm","sonar");
+    setupConfig.sonarCAN_ID = std::strtoul(xp.GetParam("sonarCAN_ID","0x301").c_str(),0,0);
+
+//    std::cout<<"canrecv_shm : "<<setupConfig.strMemCANRecv<<std::endl;
+//    std::cout<<"cansend_shm : "<<setupConfig.strMemCANSend<<std::endl;
+//    std::cout<<"sonarCAN_ID : "<<setupConfig.sonarCAN_ID<<std::endl;
+
+    return 0;
+}

+ 19 - 0
src/driver/driver_ultrasonic_dauxi_KS136A/decode_cfg.h

@@ -0,0 +1,19 @@
+#ifndef DECODE_CFG_H
+#define DECODE_CFG_H
+
+#include <iostream>
+
+#include "xmlparam.h"
+#include <yaml-cpp/yaml.h>
+
+struct setupConfig_t
+{
+    std::string strMemCANRecv = "canrecv0";
+    std::string strMemCANSend = "cansend0";
+    std::string strMemSonar = "sonar";
+    uint32_t sonarCAN_ID = 0x301;
+};
+
+int DecodeSonarCfgFromXML(setupConfig_t &setupConfig , const std::string &xmlFilePath);
+
+#endif // DECODE_CFG_H

+ 57 - 0
src/driver/driver_ultrasonic_dauxi_KS136A/driver_ultrasonic_dauxi_KS136A.pro

@@ -0,0 +1,57 @@
+QT -= gui
+
+QT += xml dbus
+CONFIG += c++11 console
+CONFIG -= app_bundle
+
+# The following define makes your compiler emit warnings if you use
+# any Qt feature that has been marked deprecated (the exact warnings
+# depend on your compiler). Please consult the documentation of the
+# deprecated API in order to know how to port your code away from it.
+DEFINES += QT_DEPRECATED_WARNINGS
+
+# You can also make your code fail to compile if it uses deprecated APIs.
+# In order to do so, uncomment the following line.
+# You can also select to disable deprecated APIs only up to a certain version of Qt.
+#DEFINES += QT_DISABLE_DEPRECATED_BEFORE=0x060000    # disables all the APIs deprecated before Qt 6.0.0
+
+QMAKE_LFLAGS += -no-pie
+
+SOURCES += \
+        ../../include/msgtype/canmsg.pb.cc \
+        ../../include/msgtype/canraw.pb.cc \
+        ../../include/msgtype/ultrasonic.pb.cc \
+        can_producer_consumer.cpp \
+        canrecv_consumer.cpp \
+        cansend_consumer.cpp \
+        cansend_producer.cpp \
+        decode_cfg.cpp \
+        main.cpp
+
+HEADERS += \
+    ../../include/msgtype/canmsg.pb.h \
+    ../../include/msgtype/canraw.pb.h \
+    ../../include/msgtype/ultrasonic.pb.h \
+    can_producer_consumer.h \
+    canrecv_consumer.h \
+    cansend_consumer.h \
+    cansend_producer.h \
+    decode_cfg.h \
+    iv_msgunit.h
+
+# Default rules for deployment.
+qnx: target.path = /tmp/$${TARGET}/bin
+else: unix:!android: target.path = /opt/$${TARGET}/bin
+!isEmpty(target.path): INSTALLS += target
+
+!include(../../../include/common.pri ) {
+    error( "Couldn't find the common.pri file!" )
+}
+
+!include(../../../include/ivprotobuf.pri ) {
+    error( "Couldn't find the ivprotobuf.pri file!" )
+}
+
+!include(../../../include/ivyaml-cpp.pri ) {
+    error( "Couldn't find the ivyaml-cpp.pri file!" )
+}

+ 8 - 0
src/driver/driver_ultrasonic_dauxi_KS136A/driver_ultrasonic_dauxi_KS136A.xml

@@ -0,0 +1,8 @@
+<xml>	
+	<node name="driver_ultrasonic_dauxi_KS136A">
+		<param name="canrecv_shm" value="canrecv0" />
+		<param name="cansend_shm" value="cansend0" />
+		<param name="sonar_shm" value="sonar" />
+		<param name="sonarCAN_ID" value="0x301" /> <!-- recommend use hex format -->
+	</node>
+</xml>

+ 21 - 0
src/driver/driver_ultrasonic_dauxi_KS136A/iv_msgunit.h

@@ -0,0 +1,21 @@
+#ifndef IV_MSGUNIT_H
+#define IV_MSGUNIT_H
+
+#include <memory>
+
+namespace iv {
+struct msgunit
+{
+    char mstrmsgname[256];
+    int mnBufferSize = 10000;
+    int mnBufferCount = 1;
+    void * mpa = nullptr;
+    std::shared_ptr<char> mpstrmsgdata;
+    int mndatasize = 0;
+    bool mbRefresh = false;
+    bool mbImportant = false;
+    int mnkeeptime = 100;
+};
+}
+
+#endif // IV_MSGUNIT_H

+ 129 - 0
src/driver/driver_ultrasonic_dauxi_KS136A/main.cpp

@@ -0,0 +1,129 @@
+#include <QCoreApplication>
+
+#include <iostream>
+#include <thread>
+
+#include "modulecomm.h"
+#include "ivversion.h"
+#include "ivbacktrace.h"
+#include "ivfault.h"
+#include "ivlog.h"
+#include "ivexit.h"
+
+#include "canmsg.pb.h"
+
+#include "decode_cfg.h"
+#include "iv_msgunit.h"
+#include "can_producer_consumer.h"
+#include "canrecv_consumer.h"
+#include "cansend_consumer.h"
+#include "cansend_producer.h"
+
+QCoreApplication * gApp;
+
+iv::Ivfault *gfault = nullptr;
+iv::Ivlog *givlog = nullptr;
+
+setupConfig_t setupConfig;
+
+iv::msgunit shmCANRecv;
+iv::msgunit shmCANSend;
+iv::msgunit shmSonar;
+
+CAN_Producer_Consumer CANRecv(4096);
+CAN_Producer_Consumer CANSend(4096);
+
+CANSend_Producer* can_send_producer;
+CANSend_Consumer* can_send_consumer;
+//CANRecv_Consumer* can_recv_consumer;
+
+void ListenCANMsg(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
+{
+    if(nSize<1)
+    {
+        std::cout<<"radar ListenCANMsg data empty."<<std::endl;
+        return;
+    }
+    iv::can::canmsg xmsg;
+    if(!xmsg.ParseFromArray(strdata,nSize))
+    {
+        givlog->error("radar Listencanmsg fail");
+        gfault->SetFaultState(1, 0, "radar Listencanmsg error");
+        std::cout<<"radar ListenCANMsg parse fail."<<std::endl;
+        return;
+    }
+
+    CANRecv.Produce_Elements_From_CANMsg(xmsg);
+}
+
+void ExitFunc()
+{
+    gApp->quit();
+    std::this_thread::sleep_for(std::chrono::milliseconds(500));
+}
+
+void signal_handler(int sig)
+{
+    if(sig == SIGINT)
+    {
+        ExitFunc();
+    }
+}
+
+int main(int argc, char *argv[])
+{
+    RegisterIVBackTrace();
+    showversion("driver_ultrasonic_dauxi_KS136A");
+    QCoreApplication a(argc, argv);
+
+    gApp = &a;
+
+    givlog = new iv::Ivlog("driver_ultrasonic_dauxi_KS136A");
+    gfault = new iv::Ivfault("driver_ultrasonic_dauxi_KS136A");
+
+    signal(SIGINT,signal_handler);
+
+    QString strpath = QCoreApplication::applicationDirPath();
+    if(argc < 2)
+        strpath = strpath + "/driver_ultrasonic_dauxi_KS136A.xml";
+    else
+        strpath = argv[1];
+
+    DecodeSonarCfgFromXML(setupConfig,strpath.toStdString());
+
+    strncpy(shmCANSend.mstrmsgname,setupConfig.strMemCANSend.data(),255);
+    shmCANSend.mnBufferSize = 100000;
+    shmCANSend.mnBufferCount = 3;
+    shmCANSend.mpa = iv::modulecomm::RegisterSend(shmCANSend.mstrmsgname,shmCANSend.mnBufferSize,shmCANSend.mnBufferCount);
+
+    strncpy(shmSonar.mstrmsgname,setupConfig.strMemSonar.data(),255);
+    shmSonar.mnBufferSize = 100000;
+    shmSonar.mnBufferCount = 1;
+    shmSonar.mpa = iv::modulecomm::RegisterSend(shmSonar.mstrmsgname,shmSonar.mnBufferSize,shmSonar.mnBufferCount);
+
+    strncpy(shmCANRecv.mstrmsgname,setupConfig.strMemCANRecv.data(),255);
+    shmCANRecv.mnBufferSize = 100000;
+    shmCANRecv.mnBufferCount = 3;
+    shmCANRecv.mpa = iv::modulecomm::RegisterRecv(shmCANRecv.mstrmsgname,ListenCANMsg);
+
+    can_send_producer = new CANSend_Producer(&CANSend);
+    can_send_producer->start();
+    can_send_consumer = new CANSend_Consumer(&CANSend);
+    can_send_consumer->start();
+//    can_recv_consumer = new CANRecv_Consumer(&CANRecv);
+//    can_recv_consumer->start();
+
+    int rtn = a.exec();
+
+    can_send_producer->terminate(); //function "terminate" can not be used in other position. it is dangerous.
+    can_send_consumer->terminate(); //function "terminate" can not be used in other position. it is dangerous.
+//    can_recv_consumer->terminate(); //function "terminate" can not be used in other position. it is dangerous.
+
+    if(gfault != nullptr)delete gfault;
+    if(givlog != nullptr)delete givlog;
+    if(shmCANRecv.mpa != nullptr)iv::modulecomm::Unregister(shmCANRecv.mpa);
+    if(shmCANSend.mpa != nullptr)iv::modulecomm::Unregister(shmCANSend.mpa);
+    if(shmSonar.mpa != nullptr)iv::modulecomm::Unregister(shmSonar.mpa);
+
+    return rtn;
+}

+ 29 - 28
src/include/proto/ultrasonic.proto

@@ -19,36 +19,37 @@ package iv.ultrasonic;
 
 message ultrasonic
 {
-	required uint32 sigObjDist_FLSide   = 1; //前左区域距离显示
-	required uint32 sigObjDist_FLCorner = 2; //前左角
-	required uint32 sigObjDist_FLMiddle = 3; //前中左
-	required uint32 sigObjDist_FRMiddle = 4; //前中右
-	required uint32 sigObjDist_FRCorner = 5; //前右角
-	required uint32 sigObjDist_FRSide   = 6; //前右侧
-	required uint32 sigObjDist_RLSide   = 7; //后左侧
-	required uint32 sigObjDist_RLCorner = 8; //后左角
-	required uint32 sigObjDist_RLMiddle = 9; //后中左
-	required uint32 sigObjDist_RRMiddle = 10;//后中右
-	required uint32 sigObjDist_RRCorner = 11;//后右角
-	required uint32 sigObjDist_RRSide   = 12;//后右侧
+	optional uint32 sigObjDist_FLSide   = 1; //前左区域距离显示
+	optional uint32 sigObjDist_FLCorner = 2; //前左角
+	optional uint32 sigObjDist_FLMiddle = 3; //前中左
+	optional uint32 sigObjDist_FRMiddle = 4; //前中右
+	optional uint32 sigObjDist_FRCorner = 5; //前右角
+	optional uint32 sigObjDist_FRSide   = 6; //前右侧
+	optional uint32 sigObjDist_RLSide   = 7; //后左侧
+	optional uint32 sigObjDist_RLCorner = 8; //后左角
+	optional uint32 sigObjDist_RLMiddle = 9; //后中左
+	optional uint32 sigObjDist_RRMiddle = 10;//后中右
+	optional uint32 sigObjDist_RRCorner = 11;//后右角
+	optional uint32 sigObjDist_RRSide   = 12;//后右侧
 
-	required uint32 sigSensor_Front_LS  = 13;//前左侧运行状态显示
-	required uint32 sigSensor_Front_L   = 14;//前左角运行状态显示
-	required uint32 sigSensor_Front_LM  = 15;//前中左
-	required uint32 sigSensor_Front_RM  = 16;//前中右
-	required uint32 sigSensor_Front_R   = 17;//前右角
-	required uint32 sigSensor_Front_RS  = 18;//前右侧
-	required uint32 sigSensor_Rear_L	= 19;//后左角
-	required uint32 sigSensor_Rear_LS   = 20;//后左侧
-	required uint32 sigSensor_Rear_LM   = 21;//后左中
-	required uint32 sigSensor_Rear_R    = 22;//后右角
-	required uint32 sigSensor_Rear_RS   = 23;//后右侧
-	required uint32 sigSensor_Rear_RM   = 24;//后右中
+	optional uint32 sigSensor_Front_LS  = 13;//前左侧运行状态显示
+	optional uint32 sigSensor_Front_L   = 14;//前左角运行状态显示
+	optional uint32 sigSensor_Front_LM  = 15;//前中左
+	optional uint32 sigSensor_Front_RM  = 16;//前中右
+	optional uint32 sigSensor_Front_R   = 17;//前右角
+	optional uint32 sigSensor_Front_RS  = 18;//前右侧
+	optional uint32 sigSensor_Rear_L	= 19;//后左角
+	optional uint32 sigSensor_Rear_LS   = 20;//后左侧
+	optional uint32 sigSensor_Rear_LM   = 21;//后左中
+	optional uint32 sigSensor_Rear_R    = 22;//后右角
+	optional uint32 sigSensor_Rear_RS   = 23;//后右侧
+	optional uint32 sigSensor_Rear_RM   = 24;//后右中
 
-	required uint32 sigCANVoltageSt	    = 25;
-	required uint32 sigPAVoltageSt	    = 26;
-	required uint32 sigDTCVoltageSt	    = 27;
-	required uint32 sigSensPwrSt		= 28;
+	optional uint32 sigCANVoltageSt = 25;
+	optional uint32 sigPAVoltageSt = 26;
+	optional uint32 sigDTCVoltageSt = 27;
+	optional uint32 sigSensPwrSt = 28;
 	
+	required uint64 timeStamp = 29;	
 }