Browse Source

fix(driver_sonar_ks136a,driver_radar_ars408):finish sonar driver coding, ready to test. fix some code format mistake in ars408 driver

孙嘉城 3 years ago
parent
commit
57e75c31fd

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

@@ -66,7 +66,7 @@ uint64_t CAN_Producer_Consumer::Produce_Elements_From_CANMsg(const iv::can::canm
     return tempPtr;
 }
 
-iv::can::canraw CAN_Producer_Consumer::Consume_Element()
+iv::can::canraw CAN_Producer_Consumer::Consume_Element(void)
 {
     iv::can::canraw xraw;
     usedSpace.acquire(); //this function is block mode

+ 1 - 1
src/driver/driver_radar_continental_ARS408_SRR308/can_producer_consumer.h

@@ -16,7 +16,7 @@ public:
     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::canraw Consume_Element(void);
     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
 

+ 53 - 53
src/driver/driver_radar_continental_ARS408_SRR308/canrecv_consumer.cpp

@@ -83,9 +83,9 @@ void CANRecv_Consumer::Pack_Info_To_SHM_ch0(uint32_t can_id)
             xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
             xradarObjArray.set_radar_version(radar_Version);
 
-            radarObjArraySend_lock.lock();
-            radarObjArray_send.CopyFrom(xradarObjArray);
-            radarObjArraySend_lock.unlock();
+            radarObjArraySend_Lock.lock();
+            radarObjArray_Send.CopyFrom(xradarObjArray);
+            radarObjArraySend_Lock.unlock();
             emit RadarObjectArray_Ready();
         }
         else
@@ -109,9 +109,9 @@ void CANRecv_Consumer::Pack_Info_To_SHM_ch0(uint32_t can_id)
             xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
             xradarObjArray.set_radar_version(radar_Version);
 
-            radarObjArraySend_lock.lock();
-            radarObjArray_send.CopyFrom(xradarObjArray);
-            radarObjArraySend_lock.unlock();
+            radarObjArraySend_Lock.lock();
+            radarObjArray_Send.CopyFrom(xradarObjArray);
+            radarObjArraySend_Lock.unlock();
 //            std::cout<<radarObjArray_send.obj_size()<<std::endl;
             emit RadarObjectArray_Ready();
         }
@@ -208,9 +208,9 @@ void CANRecv_Consumer::Pack_Info_To_SHM_ch1(uint32_t can_id)
             xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
             xradarObjArray.set_radar_version(radar_Version);
 
-            radarObjArraySend_lock.lock();
-            radarObjArray_send.CopyFrom(xradarObjArray);
-            radarObjArraySend_lock.unlock();
+            radarObjArraySend_Lock.lock();
+            radarObjArray_Send.CopyFrom(xradarObjArray);
+            radarObjArraySend_Lock.unlock();
             emit RadarObjectArray_Ready();
         }
         else
@@ -234,9 +234,9 @@ void CANRecv_Consumer::Pack_Info_To_SHM_ch1(uint32_t can_id)
             xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
             xradarObjArray.set_radar_version(radar_Version);
 
-            radarObjArraySend_lock.lock();
-            radarObjArray_send.CopyFrom(xradarObjArray);
-            radarObjArraySend_lock.unlock();
+            radarObjArraySend_Lock.lock();
+            radarObjArray_Send.CopyFrom(xradarObjArray);
+            radarObjArraySend_Lock.unlock();
 //            std::cout<<radarObjArray_send.obj_size()<<std::endl;
             emit RadarObjectArray_Ready();
         }
@@ -333,9 +333,9 @@ void CANRecv_Consumer::Pack_Info_To_SHM_ch2(uint32_t can_id)
             xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
             xradarObjArray.set_radar_version(radar_Version);
 
-            radarObjArraySend_lock.lock();
-            radarObjArray_send.CopyFrom(xradarObjArray);
-            radarObjArraySend_lock.unlock();
+            radarObjArraySend_Lock.lock();
+            radarObjArray_Send.CopyFrom(xradarObjArray);
+            radarObjArraySend_Lock.unlock();
             emit RadarObjectArray_Ready();
         }
         else
@@ -359,9 +359,9 @@ void CANRecv_Consumer::Pack_Info_To_SHM_ch2(uint32_t can_id)
             xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
             xradarObjArray.set_radar_version(radar_Version);
 
-            radarObjArraySend_lock.lock();
-            radarObjArray_send.CopyFrom(xradarObjArray);
-            radarObjArraySend_lock.unlock();
+            radarObjArraySend_Lock.lock();
+            radarObjArray_Send.CopyFrom(xradarObjArray);
+            radarObjArraySend_Lock.unlock();
 //            std::cout<<radarObjArray_send.obj_size()<<std::endl;
             emit RadarObjectArray_Ready();
         }
@@ -458,9 +458,9 @@ void CANRecv_Consumer::Pack_Info_To_SHM_ch3(uint32_t can_id)
             xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
             xradarObjArray.set_radar_version(radar_Version);
 
-            radarObjArraySend_lock.lock();
-            radarObjArray_send.CopyFrom(xradarObjArray);
-            radarObjArraySend_lock.unlock();
+            radarObjArraySend_Lock.lock();
+            radarObjArray_Send.CopyFrom(xradarObjArray);
+            radarObjArraySend_Lock.unlock();
             emit RadarObjectArray_Ready();
         }
         else
@@ -484,9 +484,9 @@ void CANRecv_Consumer::Pack_Info_To_SHM_ch3(uint32_t can_id)
             xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
             xradarObjArray.set_radar_version(radar_Version);
 
-            radarObjArraySend_lock.lock();
-            radarObjArray_send.CopyFrom(xradarObjArray);
-            radarObjArraySend_lock.unlock();
+            radarObjArraySend_Lock.lock();
+            radarObjArray_Send.CopyFrom(xradarObjArray);
+            radarObjArraySend_Lock.unlock();
 //            std::cout<<radarObjArray_send.obj_size()<<std::endl;
             emit RadarObjectArray_Ready();
         }
@@ -583,9 +583,9 @@ void CANRecv_Consumer::Pack_Info_To_SHM_ch4(uint32_t can_id)
             xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
             xradarObjArray.set_radar_version(radar_Version);
 
-            radarObjArraySend_lock.lock();
-            radarObjArray_send.CopyFrom(xradarObjArray);
-            radarObjArraySend_lock.unlock();
+            radarObjArraySend_Lock.lock();
+            radarObjArray_Send.CopyFrom(xradarObjArray);
+            radarObjArraySend_Lock.unlock();
             emit RadarObjectArray_Ready();
         }
         else
@@ -609,9 +609,9 @@ void CANRecv_Consumer::Pack_Info_To_SHM_ch4(uint32_t can_id)
             xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
             xradarObjArray.set_radar_version(radar_Version);
 
-            radarObjArraySend_lock.lock();
-            radarObjArray_send.CopyFrom(xradarObjArray);
-            radarObjArraySend_lock.unlock();
+            radarObjArraySend_Lock.lock();
+            radarObjArray_Send.CopyFrom(xradarObjArray);
+            radarObjArraySend_Lock.unlock();
 //            std::cout<<radarObjArray_send.obj_size()<<std::endl;
             emit RadarObjectArray_Ready();
         }
@@ -708,9 +708,9 @@ void CANRecv_Consumer::Pack_Info_To_SHM_ch5(uint32_t can_id)
             xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
             xradarObjArray.set_radar_version(radar_Version);
 
-            radarObjArraySend_lock.lock();
-            radarObjArray_send.CopyFrom(xradarObjArray);
-            radarObjArraySend_lock.unlock();
+            radarObjArraySend_Lock.lock();
+            radarObjArray_Send.CopyFrom(xradarObjArray);
+            radarObjArraySend_Lock.unlock();
             emit RadarObjectArray_Ready();
         }
         else
@@ -734,9 +734,9 @@ void CANRecv_Consumer::Pack_Info_To_SHM_ch5(uint32_t can_id)
             xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
             xradarObjArray.set_radar_version(radar_Version);
 
-            radarObjArraySend_lock.lock();
-            radarObjArray_send.CopyFrom(xradarObjArray);
-            radarObjArraySend_lock.unlock();
+            radarObjArraySend_Lock.lock();
+            radarObjArray_Send.CopyFrom(xradarObjArray);
+            radarObjArraySend_Lock.unlock();
 //            std::cout<<radarObjArray_send.obj_size()<<std::endl;
             emit RadarObjectArray_Ready();
         }
@@ -833,9 +833,9 @@ void CANRecv_Consumer::Pack_Info_To_SHM_ch6(uint32_t can_id)
             xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
             xradarObjArray.set_radar_version(radar_Version);
 
-            radarObjArraySend_lock.lock();
-            radarObjArray_send.CopyFrom(xradarObjArray);
-            radarObjArraySend_lock.unlock();
+            radarObjArraySend_Lock.lock();
+            radarObjArray_Send.CopyFrom(xradarObjArray);
+            radarObjArraySend_Lock.unlock();
             emit RadarObjectArray_Ready();
         }
         else
@@ -859,9 +859,9 @@ void CANRecv_Consumer::Pack_Info_To_SHM_ch6(uint32_t can_id)
             xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
             xradarObjArray.set_radar_version(radar_Version);
 
-            radarObjArraySend_lock.lock();
-            radarObjArray_send.CopyFrom(xradarObjArray);
-            radarObjArraySend_lock.unlock();
+            radarObjArraySend_Lock.lock();
+            radarObjArray_Send.CopyFrom(xradarObjArray);
+            radarObjArraySend_Lock.unlock();
 //            std::cout<<radarObjArray_send.obj_size()<<std::endl;
             emit RadarObjectArray_Ready();
         }
@@ -958,9 +958,9 @@ void CANRecv_Consumer::Pack_Info_To_SHM_ch7(uint32_t can_id)
             xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
             xradarObjArray.set_radar_version(radar_Version);
 
-            radarObjArraySend_lock.lock();
-            radarObjArray_send.CopyFrom(xradarObjArray);
-            radarObjArraySend_lock.unlock();
+            radarObjArraySend_Lock.lock();
+            radarObjArray_Send.CopyFrom(xradarObjArray);
+            radarObjArraySend_Lock.unlock();
             emit RadarObjectArray_Ready();
         }
         else
@@ -984,9 +984,9 @@ void CANRecv_Consumer::Pack_Info_To_SHM_ch7(uint32_t can_id)
             xradarObjArray.set_yaw_rate_loss(yaw_Rate_Loss);
             xradarObjArray.set_radar_version(radar_Version);
 
-            radarObjArraySend_lock.lock();
-            radarObjArray_send.CopyFrom(xradarObjArray);
-            radarObjArraySend_lock.unlock();
+            radarObjArraySend_Lock.lock();
+            radarObjArray_Send.CopyFrom(xradarObjArray);
+            radarObjArraySend_Lock.unlock();
 //            std::cout<<radarObjArray_send.obj_size()<<std::endl;
             emit RadarObjectArray_Ready();
         }
@@ -1236,14 +1236,14 @@ void CANRecv_Consumer::run()
     }
 }
 
-void CANRecv_Consumer::RadarObjectArray_Ready_Slot()
+void CANRecv_Consumer::RadarObjectArray_Ready_Slot(void)
 {
-    radarObjArraySend_lock.lock();
-    int ndatasize = radarObjArray_send.ByteSize();
+    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))
+    if(radarObjArray_Send.SerializePartialToArray(strser,ndatasize))
     {
         iv::modulecomm::ModuleSendMsg(shmRadar.mpa,strser,ndatasize);
     }
@@ -1251,5 +1251,5 @@ void CANRecv_Consumer::RadarObjectArray_Ready_Slot()
     {
         std::cout<<"RadarObjectArray serialize error."<<std::endl;
     }
-    radarObjArraySend_lock.unlock();
+    radarObjArraySend_Lock.unlock();
 }

+ 4 - 4
src/driver/driver_radar_continental_ARS408_SRR308/canrecv_consumer.h

@@ -42,10 +42,10 @@ protected:
     void Rotate_Translate(double &x,double &y,double theta,double offset_x,double offset_y); //RFU,deg
 
 signals:
-    void RadarObjectArray_Ready();
+    void RadarObjectArray_Ready(void);
 
 private slots:
-    void RadarObjectArray_Ready_Slot();
+    void RadarObjectArray_Ready_Slot(void);
 
 private:
     CAN_Producer_Consumer *pBuffer;
@@ -78,8 +78,8 @@ private:
     bool yaw_Rate_Loss = false; //
     std::string radar_Version = "4.30.1"; //
 
-    iv::radar::radarobjectarray radarObjArray_send;
-    QMutex radarObjArraySend_lock;
+    iv::radar::radarobjectarray radarObjArray_Send;
+    QMutex radarObjArraySend_Lock;
 };
 
 #endif // CANRECV_CONSUMER_H

+ 32 - 1
src/driver/driver_ultrasonic_dauxi_KS136A/can_producer_consumer.cpp

@@ -66,7 +66,7 @@ uint64_t CAN_Producer_Consumer::Produce_Elements_From_CANMsg(const iv::can::canm
     return tempPtr;
 }
 
-iv::can::canraw CAN_Producer_Consumer::Consume_Element()
+iv::can::canraw CAN_Producer_Consumer::Consume_Element(void)
 {
     iv::can::canraw xraw;
     usedSpace.acquire(); //this function is block mode
@@ -78,6 +78,21 @@ iv::can::canraw CAN_Producer_Consumer::Consume_Element()
     return xraw;
 }
 
+iv::can::canraw CAN_Producer_Consumer::Consume_Element(int timeout)
+{
+    iv::can::canraw xraw;
+    bool tempResult = usedSpace.tryAcquire(1,timeout);
+    if(tempResult)
+    {
+        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;
@@ -105,3 +120,19 @@ uint64_t CAN_Producer_Consumer::Consume_Element_To_CANMsg(iv::can::canmsg &xmsg)
 
     return tempPtr;
 }
+
+uint64_t CAN_Producer_Consumer::Consume_Element_To_CANMsg(iv::can::canmsg &xmsg,int timeout)
+{
+    uint64_t tempPtr = consumerPtr % bufferSize;
+    bool tempResult = usedSpace.tryAcquire(1,timeout); //this function is block mode
+    if(tempResult)
+    {
+        iv::can::canraw *praw = xmsg.add_rawmsg();
+        consumerLock.lock();
+        praw->CopyFrom(buffer.at(consumerPtr++ % bufferSize));
+        consumerLock.unlock();
+        freeSpace.release();
+    }
+
+    return tempPtr;
+}

+ 3 - 1
src/driver/driver_ultrasonic_dauxi_KS136A/can_producer_consumer.h

@@ -16,9 +16,11 @@ public:
     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::canraw Consume_Element(void);
+    iv::can::canraw Consume_Element(int timeout); //not block mode
     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
+    uint64_t Consume_Element_To_CANMsg(iv::can::canmsg &xmsg,int timeout); //not block mode
 
     QVector<iv::can::canraw> buffer;
 

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

@@ -1,1255 +1,169 @@
-//#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();
-//}
+#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::UltrasonicData_Ready,this,&CANRecv_Consumer::UltrasonicData_Ready_Slot);
+
+    objDist.fill(DIST_ERROR,NUM_OF_SENSOR_MAX);
+    sensorStatus.fill(false,NUM_OF_SENSOR_MAX);
+}
+
+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::run()
+{
+    iv::can::canraw tempCANRaw;
+    uint8_t tempSensorID = 0;
+    decodeTimer.start();
+
+    while (!QThread::isInterruptionRequested())
+    {
+        tempCANRaw.CopyFrom(pBuffer->Consume_Element(1));
+        if(decodeEnableFlag == true)
+        {
+            if(decodeTimer.elapsed() >= 25)
+            {
+                decodeEnableFlag = false;
+                objDist[decodeSensorID] = DIST_ERROR;
+                sensorStatus[decodeSensorID] = false;
+                tempSensorID = decodeSensorID + 1;
+                if(tempSensorID >= NUM_OF_SENSOR_MAX)
+                {
+                    //copy and send
+                    sonarSend_Lock.lock();
+                    objDist_Send.clear();
+                    sensorStatus_Send.clear();
+                    objDist_Send.swap(objDist);
+                    sensorStatus_Send.swap(sensorStatus);
+                    sonarSend_Lock.unlock();
+                    emit UltrasonicData_Ready();
+                    //clear
+                    objDist.fill(DIST_ERROR,NUM_OF_SENSOR_MAX);
+                    sensorStatus.fill(false,NUM_OF_SENSOR_MAX);
+                    tempSensorID = 0;
+                }
+                emit Enable_Ask(true,tempSensorID);
+                decodeTimer.restart();
+            }
+            else
+            {
+                this->Trans_From_CANRaw(tempCANRaw);
+                if(CAN_ID == setupConfig.sonarCAN_ID && CAN_DLC == 2)
+                {
+                    uint16_t tempDist = (CAN_data[0] << 8) | CAN_data[1];
+                    if(tempDist <= 0x1493 && tempDist >= 0x88)
+                    {
+                        decodeEnableFlag = false;
+                        objDist[decodeSensorID] = tempDist;
+                        sensorStatus[decodeSensorID] = true;
+                        tempSensorID = decodeSensorID + 1;
+                        if(tempSensorID >= NUM_OF_SENSOR_MAX)
+                        {
+                            //copy and send
+                            sonarSend_Lock.lock();
+                            objDist_Send.clear();
+                            sensorStatus_Send.clear();
+                            objDist_Send.swap(objDist);
+                            sensorStatus_Send.swap(sensorStatus);
+                            sonarSend_Lock.unlock();
+                            emit UltrasonicData_Ready();
+                            //clear
+                            objDist.fill(DIST_ERROR,NUM_OF_SENSOR_MAX);
+                            sensorStatus.fill(false,NUM_OF_SENSOR_MAX);
+                            tempSensorID = 0;
+                        }
+                        emit Enable_Ask(true,tempSensorID);
+                        decodeTimer.restart();
+                    }
+                }
+            }
+        }
+    }
+}
+
+void CANRecv_Consumer::Enable_DecodeResult_Slot(bool enableFlag,uint8_t sensorID)
+{
+    decodeEnableFlag = enableFlag;
+    decodeSensorID = sensorID;
+    decodeTimer.restart();
+}
+
+void CANRecv_Consumer::UltrasonicData_Ready_Slot(void)
+{
+    iv::ultrasonic::ultrasonic xmsg;
+    sonarSend_Lock.lock();
+    xmsg.set_sigobjdist_flside(objDist_Send[0]);
+    xmsg.set_sigobjdist_flcorner(objDist_Send[1]);
+    xmsg.set_sigobjdist_flmiddle(objDist_Send[2]);
+    xmsg.set_sigobjdist_frmiddle(objDist_Send[3]);
+    xmsg.set_sigobjdist_frcorner(objDist_Send[4]);
+    xmsg.set_sigobjdist_frside(objDist_Send[5]);
+    xmsg.set_sigobjdist_rrside(objDist_Send[6]);
+    xmsg.set_sigobjdist_rrcorner(objDist_Send[7]);
+    xmsg.set_sigobjdist_rrmiddle(objDist_Send[8]);
+    xmsg.set_sigobjdist_rlmiddle(objDist_Send[9]);
+    xmsg.set_sigobjdist_rlcorner(objDist_Send[10]);
+    xmsg.set_sigobjdist_rlside(objDist_Send[11]);
+
+    xmsg.set_sigsensor_front_ls(sensorStatus_Send[0]);
+    xmsg.set_sigsensor_front_l(sensorStatus_Send[1]);
+    xmsg.set_sigsensor_front_lm(sensorStatus_Send[2]);
+    xmsg.set_sigsensor_front_rm(sensorStatus_Send[3]);
+    xmsg.set_sigsensor_front_r(sensorStatus_Send[4]);
+    xmsg.set_sigsensor_front_rs(sensorStatus_Send[5]);
+    xmsg.set_sigsensor_rear_rs(sensorStatus_Send[6]);
+    xmsg.set_sigsensor_rear_r(sensorStatus_Send[7]);
+    xmsg.set_sigsensor_rear_rm(sensorStatus_Send[8]);
+    xmsg.set_sigsensor_rear_lm(sensorStatus_Send[9]);
+    xmsg.set_sigsensor_rear_l(sensorStatus_Send[10]);
+    xmsg.set_sigsensor_rear_ls(sensorStatus_Send[11]);
+    sonarSend_Lock.unlock();
+
+    xmsg.set_timestamp(QDateTime::currentMSecsSinceEpoch());
+    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(shmSonar.mpa,strser,ndatasize);
+    }
+    else
+    {
+        std::cout<<"ultrasonic data serialize error."<<std::endl;
+    }
+}

+ 60 - 80
src/driver/driver_ultrasonic_dauxi_KS136A/canrecv_consumer.h

@@ -1,85 +1,65 @@
 #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;
-//};
+#include <QObject>
+#include <QTimer>
+#include <QDateTime>
+#include <QThread>
+
+#include "modulecomm.h"
+#include "ultrasonic.pb.h"
+
+#include "can_producer_consumer.h"
+#include "decode_cfg.h"
+#include "iv_msgunit.h"
+
+#ifndef NUM_OF_SENSOR_MAX
+#define NUM_OF_SENSOR_MAX 12
+#endif
+
+#ifndef DIST_ERROR
+#define DIST_ERROR 50000 //50000mm
+#endif
+
+class CANRecv_Consumer : public QThread
+{
+    Q_OBJECT
+public:
+    CANRecv_Consumer(CAN_Producer_Consumer *pBuf);
+    ~CANRecv_Consumer();
+    void Clear_CAN_PrivateTempVariable(void);
+
+public slots:
+    void Enable_DecodeResult_Slot(bool enableFlag,uint8_t sensorID);
+
+protected:
+    void run();
+    uint32_t Trans_From_CANRaw(const iv::can::canraw &xraw); //only for standard data frame, return can id
+
+signals:
+    void Enable_Ask(bool enableFlag,uint8_t sensorID);
+    void UltrasonicData_Ready(void);
+
+private slots:
+    void UltrasonicData_Ready_Slot(void);
+
+private:
+    CAN_Producer_Consumer *pBuffer;
+
+    uint32_t CAN_ID = 0x000u;
+    uint8_t CAN_DLC = 0;
+    uint8_t CAN_data[8] = {0};
+
+    bool decodeEnableFlag = false;
+    uint8_t decodeSensorID = 0;
+    QTime decodeTimer;
+
+    QVector<uint32_t> objDist;
+    QVector<bool> sensorStatus;
+
+    QVector<uint32_t> objDist_Send;
+    QVector<bool> sensorStatus_Send;
+    QMutex sonarSend_Lock;
+};
 
 #endif // CANRECV_CONSUMER_H

+ 19 - 33
src/driver/driver_ultrasonic_dauxi_KS136A/cansend_consumer.cpp

@@ -18,12 +18,6 @@ CANSend_Consumer::~CANSend_Consumer()
 
 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;
@@ -35,37 +29,29 @@ void CANSend_Consumer::run()
 
     while (!QThread::isInterruptionRequested())
     {
-        pBuffer->Consume_Element_To_CANMsg(xmsg); //this function is block mode
-
-        if(abs(xTime.elapsed() - lastTime)>=interval || xmsg.rawmsg_size() > 3500)
+        pBuffer->Consume_Element_To_CANMsg(xmsg);
+        if(xmsg.rawmsg_size()>0)
         {
-            //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))
             {
-                //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++;
+                iv::modulecomm::ModuleSendMsg(shmCANSend.mpa,strser,ndatasize);
             }
             else
-                std::cout << "rawmsg size is zero, no data need to be send." << std::endl;
+            {
+                std::cout<<"CANSend_Consumer serialize error."<<std::endl;
+            }
+            //clear and update index
+            xmsg.clear_rawmsg();
+            CANPackageIndex++;
         }
     }
 }

+ 16 - 11
src/driver/driver_ultrasonic_dauxi_KS136A/cansend_producer.cpp

@@ -41,26 +41,25 @@ iv::can::canraw CANSend_Producer::Trans_to_CANRaw(void)
 
 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)
+        if(askEnableFlag == true)
         {
-            //update timer
-            lastTime = xTime.elapsed();
+            askEnableFlag = false;
 
             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());
+            if(askSensorID < NUM_OF_SENSOR_MAX)
+            {
+                CAN_data[2] =  askSensorID * 8 + 0x16;
+                pBuffer->Produce_Element(this->Trans_to_CANRaw());
+                emit Enable_DecodeResult(true,askSensorID);
+            }
+            else
+                std::cout<<"askSensorID is error"<<std::endl;
         }
         else
         {
@@ -68,3 +67,9 @@ void CANSend_Producer::run()
         }
     }
 }
+
+void CANSend_Producer::Enable_Ask_Slot(bool enableFlag , uint8_t sensorID)
+{
+    askEnableFlag = enableFlag;
+    askSensorID = sensorID;
+}

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

@@ -11,6 +11,10 @@
 #include "can_producer_consumer.h"
 #include "decode_cfg.h"
 
+#ifndef NUM_OF_SENSOR_MAX
+#define NUM_OF_SENSOR_MAX 12
+#endif
+
 class CANSend_Producer : public QThread
 {
     Q_OBJECT
@@ -19,6 +23,9 @@ public:
     ~CANSend_Producer();
     void Clear_CAN_PrivateTempVariable(void);
 
+public slots:
+    void Enable_Ask_Slot(bool enableFlag,uint8_t sensorID);
+
 protected:
     void run();
     iv::can::canraw Trans_to_CANRaw(void);
@@ -31,6 +38,12 @@ private:
     uint8_t CAN_RTR = 0;
     uint8_t CAN_DLC = 0;
     uint8_t CAN_data[8] = {0};
+
+    bool askEnableFlag = true;
+    uint8_t askSensorID = 0;
+
+signals:
+    void Enable_DecodeResult(bool enableFlag,uint8_t sensorID);
 };
 
 #endif // CANSEND_PRODUCER_H

+ 1 - 1
src/driver/driver_ultrasonic_dauxi_KS136A/decode_cfg.cpp

@@ -7,7 +7,7 @@ int DecodeSonarCfgFromXML(setupConfig_t &setupConfig , const std::string &xmlFil
     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);
+    setupConfig.sonarCAN_ID = std::strtoul(xp.GetParam("sonarCAN_ID","0x101").c_str(),0,0);
 
 //    std::cout<<"canrecv_shm : "<<setupConfig.strMemCANRecv<<std::endl;
 //    std::cout<<"cansend_shm : "<<setupConfig.strMemCANSend<<std::endl;

+ 15 - 6
src/driver/driver_ultrasonic_dauxi_KS136A/main.cpp

@@ -12,6 +12,10 @@
 
 #include "canmsg.pb.h"
 
+#ifndef NUM_OF_SENSOR_MAX
+#define NUM_OF_SENSOR_MAX 12
+#endif
+
 #include "decode_cfg.h"
 #include "iv_msgunit.h"
 #include "can_producer_consumer.h"
@@ -35,7 +39,7 @@ CAN_Producer_Consumer CANSend(4096);
 
 CANSend_Producer* can_send_producer;
 CANSend_Consumer* can_send_consumer;
-//CANRecv_Consumer* can_recv_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)
 {
@@ -106,18 +110,23 @@ int main(int argc, char *argv[])
     shmCANRecv.mnBufferCount = 3;
     shmCANRecv.mpa = iv::modulecomm::RegisterRecv(shmCANRecv.mstrmsgname,ListenCANMsg);
 
-    can_send_producer = new CANSend_Producer(&CANSend);
-    can_send_producer->start();
+    std::this_thread::sleep_for(std::chrono::milliseconds(1000));
+
     can_send_consumer = new CANSend_Consumer(&CANSend);
     can_send_consumer->start();
-//    can_recv_consumer = new CANRecv_Consumer(&CANRecv);
-//    can_recv_consumer->start();
+    can_send_producer = new CANSend_Producer(&CANSend);
+    can_recv_consumer = new CANRecv_Consumer(&CANRecv);
+    qRegisterMetaType<uint8_t>("uint8_t");
+    QObject::connect(can_send_producer,&CANSend_Producer::Enable_DecodeResult,can_recv_consumer,&CANRecv_Consumer::Enable_DecodeResult_Slot);
+    QObject::connect(can_recv_consumer,&CANRecv_Consumer::Enable_Ask,can_send_producer,&CANSend_Producer::Enable_Ask_Slot);
+    can_send_producer->start();
+    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.
+    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;

+ 1 - 1
src/include/proto/ultrasonic.proto

@@ -19,7 +19,7 @@ package iv.ultrasonic;
 
 message ultrasonic
 {
-	optional uint32 sigObjDist_FLSide   = 1; //前左区域距离显示
+	optional uint32 sigObjDist_FLSide   = 1; //前左区域距离显示 mm
 	optional uint32 sigObjDist_FLCorner = 2; //前左角
 	optional uint32 sigObjDist_FLMiddle = 3; //前中左
 	optional uint32 sigObjDist_FRMiddle = 4; //前中右