Browse Source

fix(driver_radar_ARS408):finish coding,need to be test

孙嘉城 3 years ago
parent
commit
89849cfc1c

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

@@ -3,7 +3,7 @@
 CAN_Producer_Consumer::CAN_Producer_Consumer(const int bufSize)
 {
     bufferSize = bufSize;
-    buffer.reserve(bufferSize);
+    buffer.resize(bufferSize);
     freeSpace.release(bufferSize);
 }
 

+ 1110 - 18
src/driver/driver_radar_continental_ARS408_SRR308/canrecv_consumer.cpp

@@ -1,16 +1,19 @@
 #include "canrecv_consumer.h"
 
-#include "decode_cfg.h"
-extern setupConfig_t setupConfig;
-
-#include "radarobjectarray.pb.h"
+#include "math.h"
 
-#include "iv_msgunit.h"
+extern setupConfig_t setupConfig;
 extern iv::msgunit shmRadar;
 
 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()
@@ -19,8 +22,16 @@ CANRecv_Consumer::~CANRecv_Consumer()
     while(this->isFinished() == false);
 }
 
-uint32_t CANRecv_Consumer::Trans_From_CANRaw(const iv::can::canraw &xraw)
+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];
@@ -34,30 +45,1111 @@ uint32_t CANRecv_Consumer::Trans_From_CANRaw(const iv::can::canraw &xraw)
     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 tempVLat,tempVLong;
+    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();
+            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;
+        vradarObj[tempObjID].set_x(-ars408_can_database_ch0_rx.Obj_1_General_ch0.Obj_DistLat_phys);
+        vradarObj[tempObjID].set_y(ars408_can_database_ch0_rx.Obj_1_General_ch0.Obj_DistLong_phys);
+        tempVLat = ars408_can_database_ch0_rx.Obj_1_General_ch0.Obj_VrelLat_phys;
+        tempVLong = ars408_can_database_ch0_rx.Obj_1_General_ch0.Obj_VrelLong_phys;
+        vradarObj[tempObjID].set_vx(-tempVLat);
+        vradarObj[tempObjID].set_vy(tempVLong);
+        vradarObj[tempObjID].set_vel(sqrt(tempVLat*tempVLat+tempVLong*tempVLong));
+        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;
+        vradarObj[tempObjID].set_object_arellong(ars408_can_database_ch0_rx.Obj_3_Extended_ch0.Obj_ArelLong_phys);
+        vradarObj[tempObjID].set_object_arellat(-ars408_can_database_ch0_rx.Obj_3_Extended_ch0.Obj_ArelLat_phys);
+        vradarObj[tempObjID].set_object_orientationangle(ars408_can_database_ch0_rx.Obj_3_Extended_ch0.Obj_OrientationAngle_phys);
+        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 tempVLat,tempVLong;
+    uint8_t tempObjID;
+
+    switch (can_id) {
+    case 0x211:
+        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 0x710:
+        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 0x61A:
+        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();
+            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 0x61B:
+        tempObjID = ars408_can_database_ch1_rx.Obj_1_General_ch1.Obj_ID;
+        radarObjFreshFlag[tempObjID] = true;
+        vradarObj[tempObjID].set_x(-ars408_can_database_ch1_rx.Obj_1_General_ch1.Obj_DistLat_phys);
+        vradarObj[tempObjID].set_y(ars408_can_database_ch1_rx.Obj_1_General_ch1.Obj_DistLong_phys);
+        tempVLat = ars408_can_database_ch1_rx.Obj_1_General_ch1.Obj_VrelLat_phys;
+        tempVLong = ars408_can_database_ch1_rx.Obj_1_General_ch1.Obj_VrelLong_phys;
+        vradarObj[tempObjID].set_vx(-tempVLat);
+        vradarObj[tempObjID].set_vy(tempVLong);
+        vradarObj[tempObjID].set_vel(sqrt(tempVLat*tempVLat+tempVLong*tempVLong));
+        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 0x61C:
+        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 0x61D:
+        tempObjID = ars408_can_database_ch1_rx.Obj_3_Extended_ch1.Obj_ID;
+        vradarObj[tempObjID].set_object_arellong(ars408_can_database_ch1_rx.Obj_3_Extended_ch1.Obj_ArelLong_phys);
+        vradarObj[tempObjID].set_object_arellat(-ars408_can_database_ch1_rx.Obj_3_Extended_ch1.Obj_ArelLat_phys);
+        vradarObj[tempObjID].set_object_orientationangle(ars408_can_database_ch1_rx.Obj_3_Extended_ch1.Obj_OrientationAngle_phys);
+        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 tempVLat,tempVLong;
+    uint8_t tempObjID;
+
+    switch (can_id) {
+    case 0x221:
+        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 0x720:
+        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 0x62A:
+        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();
+            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 0x62B:
+        tempObjID = ars408_can_database_ch2_rx.Obj_1_General_ch2.Obj_ID;
+        radarObjFreshFlag[tempObjID] = true;
+        vradarObj[tempObjID].set_x(-ars408_can_database_ch2_rx.Obj_1_General_ch2.Obj_DistLat_phys);
+        vradarObj[tempObjID].set_y(ars408_can_database_ch2_rx.Obj_1_General_ch2.Obj_DistLong_phys);
+        tempVLat = ars408_can_database_ch2_rx.Obj_1_General_ch2.Obj_VrelLat_phys;
+        tempVLong = ars408_can_database_ch2_rx.Obj_1_General_ch2.Obj_VrelLong_phys;
+        vradarObj[tempObjID].set_vx(-tempVLat);
+        vradarObj[tempObjID].set_vy(tempVLong);
+        vradarObj[tempObjID].set_vel(sqrt(tempVLat*tempVLat+tempVLong*tempVLong));
+        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 0x62C:
+        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 0x62D:
+        tempObjID = ars408_can_database_ch2_rx.Obj_3_Extended_ch2.Obj_ID;
+        vradarObj[tempObjID].set_object_arellong(ars408_can_database_ch2_rx.Obj_3_Extended_ch2.Obj_ArelLong_phys);
+        vradarObj[tempObjID].set_object_arellat(-ars408_can_database_ch2_rx.Obj_3_Extended_ch2.Obj_ArelLat_phys);
+        vradarObj[tempObjID].set_object_orientationangle(ars408_can_database_ch2_rx.Obj_3_Extended_ch2.Obj_OrientationAngle_phys);
+        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 tempVLat,tempVLong;
+    uint8_t tempObjID;
+
+    switch (can_id) {
+    case 0x231:
+        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 0x730:
+        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 0x63A:
+        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();
+            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 0x63B:
+        tempObjID = ars408_can_database_ch3_rx.Obj_1_General_ch3.Obj_ID;
+        radarObjFreshFlag[tempObjID] = true;
+        vradarObj[tempObjID].set_x(-ars408_can_database_ch3_rx.Obj_1_General_ch3.Obj_DistLat_phys);
+        vradarObj[tempObjID].set_y(ars408_can_database_ch3_rx.Obj_1_General_ch3.Obj_DistLong_phys);
+        tempVLat = ars408_can_database_ch3_rx.Obj_1_General_ch3.Obj_VrelLat_phys;
+        tempVLong = ars408_can_database_ch3_rx.Obj_1_General_ch3.Obj_VrelLong_phys;
+        vradarObj[tempObjID].set_vx(-tempVLat);
+        vradarObj[tempObjID].set_vy(tempVLong);
+        vradarObj[tempObjID].set_vel(sqrt(tempVLat*tempVLat+tempVLong*tempVLong));
+        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 0x63C:
+        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 0x63D:
+        tempObjID = ars408_can_database_ch3_rx.Obj_3_Extended_ch3.Obj_ID;
+        vradarObj[tempObjID].set_object_arellong(ars408_can_database_ch3_rx.Obj_3_Extended_ch3.Obj_ArelLong_phys);
+        vradarObj[tempObjID].set_object_arellat(-ars408_can_database_ch3_rx.Obj_3_Extended_ch3.Obj_ArelLat_phys);
+        vradarObj[tempObjID].set_object_orientationangle(ars408_can_database_ch3_rx.Obj_3_Extended_ch3.Obj_OrientationAngle_phys);
+        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 tempVLat,tempVLong;
+    uint8_t tempObjID;
+
+    switch (can_id) {
+    case 0x241:
+        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 0x740:
+        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 0x64A:
+        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();
+            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 0x64B:
+        tempObjID = ars408_can_database_ch4_rx.Obj_1_General_ch4.Obj_ID;
+        radarObjFreshFlag[tempObjID] = true;
+        vradarObj[tempObjID].set_x(-ars408_can_database_ch4_rx.Obj_1_General_ch4.Obj_DistLat_phys);
+        vradarObj[tempObjID].set_y(ars408_can_database_ch4_rx.Obj_1_General_ch4.Obj_DistLong_phys);
+        tempVLat = ars408_can_database_ch4_rx.Obj_1_General_ch4.Obj_VrelLat_phys;
+        tempVLong = ars408_can_database_ch4_rx.Obj_1_General_ch4.Obj_VrelLong_phys;
+        vradarObj[tempObjID].set_vx(-tempVLat);
+        vradarObj[tempObjID].set_vy(tempVLong);
+        vradarObj[tempObjID].set_vel(sqrt(tempVLat*tempVLat+tempVLong*tempVLong));
+        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 0x64C:
+        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 0x64D:
+        tempObjID = ars408_can_database_ch4_rx.Obj_3_Extended_ch4.Obj_ID;
+        vradarObj[tempObjID].set_object_arellong(ars408_can_database_ch4_rx.Obj_3_Extended_ch4.Obj_ArelLong_phys);
+        vradarObj[tempObjID].set_object_arellat(-ars408_can_database_ch4_rx.Obj_3_Extended_ch4.Obj_ArelLat_phys);
+        vradarObj[tempObjID].set_object_orientationangle(ars408_can_database_ch4_rx.Obj_3_Extended_ch4.Obj_OrientationAngle_phys);
+        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 tempVLat,tempVLong;
+    uint8_t tempObjID;
+
+    switch (can_id) {
+    case 0x251:
+        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 0x750:
+        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 0x65A:
+        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();
+            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 0x65B:
+        tempObjID = ars408_can_database_ch5_rx.Obj_1_General_ch5.Obj_ID;
+        radarObjFreshFlag[tempObjID] = true;
+        vradarObj[tempObjID].set_x(-ars408_can_database_ch5_rx.Obj_1_General_ch5.Obj_DistLat_phys);
+        vradarObj[tempObjID].set_y(ars408_can_database_ch5_rx.Obj_1_General_ch5.Obj_DistLong_phys);
+        tempVLat = ars408_can_database_ch5_rx.Obj_1_General_ch5.Obj_VrelLat_phys;
+        tempVLong = ars408_can_database_ch5_rx.Obj_1_General_ch5.Obj_VrelLong_phys;
+        vradarObj[tempObjID].set_vx(-tempVLat);
+        vradarObj[tempObjID].set_vy(tempVLong);
+        vradarObj[tempObjID].set_vel(sqrt(tempVLat*tempVLat+tempVLong*tempVLong));
+        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 0x65C:
+        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 0x65D:
+        tempObjID = ars408_can_database_ch5_rx.Obj_3_Extended_ch5.Obj_ID;
+        vradarObj[tempObjID].set_object_arellong(ars408_can_database_ch5_rx.Obj_3_Extended_ch5.Obj_ArelLong_phys);
+        vradarObj[tempObjID].set_object_arellat(-ars408_can_database_ch5_rx.Obj_3_Extended_ch5.Obj_ArelLat_phys);
+        vradarObj[tempObjID].set_object_orientationangle(ars408_can_database_ch5_rx.Obj_3_Extended_ch5.Obj_OrientationAngle_phys);
+        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 tempVLat,tempVLong;
+    uint8_t tempObjID;
+
+    switch (can_id) {
+    case 0x261:
+        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 0x760:
+        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 0x66A:
+        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();
+            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 0x66B:
+        tempObjID = ars408_can_database_ch6_rx.Obj_1_General_ch6.Obj_ID;
+        radarObjFreshFlag[tempObjID] = true;
+        vradarObj[tempObjID].set_x(-ars408_can_database_ch6_rx.Obj_1_General_ch6.Obj_DistLat_phys);
+        vradarObj[tempObjID].set_y(ars408_can_database_ch6_rx.Obj_1_General_ch6.Obj_DistLong_phys);
+        tempVLat = ars408_can_database_ch6_rx.Obj_1_General_ch6.Obj_VrelLat_phys;
+        tempVLong = ars408_can_database_ch6_rx.Obj_1_General_ch6.Obj_VrelLong_phys;
+        vradarObj[tempObjID].set_vx(-tempVLat);
+        vradarObj[tempObjID].set_vy(tempVLong);
+        vradarObj[tempObjID].set_vel(sqrt(tempVLat*tempVLat+tempVLong*tempVLong));
+        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 0x66C:
+        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 0x66D:
+        tempObjID = ars408_can_database_ch6_rx.Obj_3_Extended_ch6.Obj_ID;
+        vradarObj[tempObjID].set_object_arellong(ars408_can_database_ch6_rx.Obj_3_Extended_ch6.Obj_ArelLong_phys);
+        vradarObj[tempObjID].set_object_arellat(-ars408_can_database_ch6_rx.Obj_3_Extended_ch6.Obj_ArelLat_phys);
+        vradarObj[tempObjID].set_object_orientationangle(ars408_can_database_ch6_rx.Obj_3_Extended_ch6.Obj_OrientationAngle_phys);
+        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 tempVLat,tempVLong;
+    uint8_t tempObjID;
+
+    switch (can_id) {
+    case 0x271:
+        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 0x770:
+        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 0x67A:
+        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();
+            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 0x67B:
+        tempObjID = ars408_can_database_ch7_rx.Obj_1_General_ch7.Obj_ID;
+        radarObjFreshFlag[tempObjID] = true;
+        vradarObj[tempObjID].set_x(-ars408_can_database_ch7_rx.Obj_1_General_ch7.Obj_DistLat_phys);
+        vradarObj[tempObjID].set_y(ars408_can_database_ch7_rx.Obj_1_General_ch7.Obj_DistLong_phys);
+        tempVLat = ars408_can_database_ch7_rx.Obj_1_General_ch7.Obj_VrelLat_phys;
+        tempVLong = ars408_can_database_ch7_rx.Obj_1_General_ch7.Obj_VrelLong_phys;
+        vradarObj[tempObjID].set_vx(-tempVLat);
+        vradarObj[tempObjID].set_vy(tempVLong);
+        vradarObj[tempObjID].set_vel(sqrt(tempVLat*tempVLat+tempVLong*tempVLong));
+        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 0x67C:
+        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 0x67D:
+        tempObjID = ars408_can_database_ch7_rx.Obj_3_Extended_ch7.Obj_ID;
+        vradarObj[tempObjID].set_object_arellong(ars408_can_database_ch7_rx.Obj_3_Extended_ch7.Obj_ArelLong_phys);
+        vradarObj[tempObjID].set_object_arellat(-ars408_can_database_ch7_rx.Obj_3_Extended_ch7.Obj_ArelLat_phys);
+        vradarObj[tempObjID].set_object_orientationangle(ars408_can_database_ch7_rx.Obj_3_Extended_ch7.Obj_OrientationAngle_phys);
+        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::run()
 {
     radarType = setupConfig.radarType;
-    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::can::canraw xraw;
+    uint32_t tempCANID = 0x000u;
 
     while (!QThread::isInterruptionRequested())
     {
         switch (setupConfig.radarID) {
         case 0:
-            xraw = pBuffer->Consume_Element();
-            this->Trans_From_CANRaw(xraw);
-            ars408_can_database_ch0_Receive(&ars408_can_database_ch0_rx,CAN_data,CAN_ID,CAN_DLC);
+            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(shmRadar.mpa,strser,ndatasize);
+    }
+    else
+    {
+        std::cout<<"RadarObjectArray serialize error."<<std::endl;
+    }
+    radarObjArraySend_lock.unlock();
+}

+ 51 - 2
src/driver/driver_radar_continental_ARS408_SRR308/canrecv_consumer.h

@@ -7,7 +7,13 @@
 #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
 {
@@ -15,11 +21,29 @@ class CANRecv_Consumer : public QThread
 public:
     CANRecv_Consumer(CAN_Producer_Consumer *pBuf);
     ~CANRecv_Consumer();
-
-    uint32_t Trans_From_CANRaw(const iv::can::canraw &xraw);
+    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);
+
+signals:
+    void RadarObjectArray_Ready();
+
+private slots:
+    void RadarObjectArray_Ready_Slot();
 
 private:
     CAN_Producer_Consumer *pBuffer;
@@ -29,6 +53,31 @@ private:
     uint32_t CAN_ID = 0x000u;
     uint8_t CAN_DLC = 0;
     uint8_t CAN_data[8] = {0};
+
+    ars408_can_database_ch0_rx_t ars408_can_database_ch0_rx;
+    ars408_can_database_ch1_rx_t ars408_can_database_ch1_rx;
+    ars408_can_database_ch2_rx_t ars408_can_database_ch2_rx;
+    ars408_can_database_ch3_rx_t ars408_can_database_ch3_rx;
+    ars408_can_database_ch4_rx_t ars408_can_database_ch4_rx;
+    ars408_can_database_ch5_rx_t ars408_can_database_ch5_rx;
+    ars408_can_database_ch6_rx_t ars408_can_database_ch6_rx;
+    ars408_can_database_ch7_rx_t ars408_can_database_ch7_rx;
+
+    iv::radar::radarobjectarray xradarObjArray;
+    QVector<iv::radar::radarobject> vradarObj;
+    QVector<bool> radarObjFreshFlag;
+
+    bool persistent_Error = false; //notice if multi thread, these param need a mutex lock
+    bool interference_Error = false; //
+    bool temperature_Error = false; //
+    bool temporary_Error = false; //
+    bool voltage_Error = false; //
+    bool speed_Loss = false; //
+    bool yaw_Rate_Loss = false; //
+    std::string radar_Version = "4.30.1"; //
+
+    iv::radar::radarobjectarray radarObjArray_send;
+    QMutex radarObjArraySend_lock;
 };
 
 #endif // CANRECV_CONSUMER_H

+ 0 - 3
src/driver/driver_radar_continental_ARS408_SRR308/cansend_consumer.cpp

@@ -1,9 +1,6 @@
 #include "cansend_consumer.h"
 
-#include "decode_cfg.h"
 extern setupConfig_t setupConfig;
-
-#include "iv_msgunit.h"
 extern iv::msgunit shmCANSend;
 
 CANSend_Consumer::CANSend_Consumer(CAN_Producer_Consumer *pBuf)

+ 3 - 0
src/driver/driver_radar_continental_ARS408_SRR308/cansend_consumer.h

@@ -7,7 +7,10 @@
 #include <QThread>
 
 #include "modulecomm.h"
+
 #include "can_producer_consumer.h"
+#include "decode_cfg.h"
+#include "iv_msgunit.h"
 
 class CANSend_Consumer : public QThread
 {

+ 45 - 36
src/driver/driver_radar_continental_ARS408_SRR308/cansend_producer.cpp

@@ -2,7 +2,6 @@
 
 #include "math.h"
 
-#include "decode_cfg.h"
 extern setupConfig_t setupConfig;
 
 extern uint8_t chassisShift;
@@ -24,14 +23,26 @@ CANSend_Producer::~CANSend_Producer()
     while(this->isFinished() == false);
 }
 
-uint32_t CANSend_Producer::Trans_to_CANRaw(iv::can::canraw &xraw)
+void CANSend_Producer::Clear_CAN_PrivateTempVariable(void)
 {
+    CAN_ID = 0x000u;
+    CAN_IDE = 0;
+    CAN_RTR = 0;
+    CAN_DLC = 0;
+    for(int i=0;i<8;i++) CAN_data[i] = 0x00;
+}
+
+iv::can::canraw CANSend_Producer::Trans_to_CANRaw(void)
+{
+    iv::can::canraw xraw;
     xraw.set_id(CAN_ID);
     xraw.set_bext(CAN_IDE);
     xraw.set_bremote(CAN_RTR);
     xraw.set_len(CAN_DLC);
     xraw.set_data(CAN_data,CAN_DLC);
     xraw.set_rectime(QDateTime::currentMSecsSinceEpoch());
+
+    return xraw;
 }
 
 void CANSend_Producer::run()
@@ -63,8 +74,6 @@ void CANSend_Producer::run()
     SpeedInformation_ch7_t SpeedInformation_ch7;
     YawRateInformation_ch7_t YawRateInformation_ch7;
 
-    iv::can::canraw xraw;
-
     int lastTime = xTime.elapsed();
     uint64_t interval = 20; //interval time should more than 10 ms
 
@@ -101,98 +110,98 @@ void CANSend_Producer::run()
             case 0:
                 SpeedInformation_ch0.RadarDevice_SpeedDirection = speedDirection;
                 SpeedInformation_ch0.RadarDevice_Speed_phys = speedFinal;
+                this->Clear_CAN_PrivateTempVariable();
                 CAN_ID = Pack_SpeedInformation_ch0_ARS408_can_database_ch0(&SpeedInformation_ch0,CAN_data,&CAN_DLC,&CAN_IDE);
-                this->Trans_to_CANRaw(xraw);
-                pBuffer->Produce_Element(xraw);
+                pBuffer->Produce_Element(this->Trans_to_CANRaw());
 
                 YawRateInformation_ch0.RadarDevice_YawRate_phys = gpsYawRate;
+                this->Clear_CAN_PrivateTempVariable();
                 CAN_ID = Pack_YawRateInformation_ch0_ARS408_can_database_ch0(&YawRateInformation_ch0,CAN_data,&CAN_DLC,&CAN_IDE);
-                this->Trans_to_CANRaw(xraw);
-                pBuffer->Produce_Element(xraw);
+                pBuffer->Produce_Element(Trans_to_CANRaw());
                 break;
             case 1:
                 SpeedInformation_ch1.RadarDevice_SpeedDirection = speedDirection;
                 SpeedInformation_ch1.RadarDevice_Speed_phys = speedFinal;
+                this->Clear_CAN_PrivateTempVariable();
                 CAN_ID = Pack_SpeedInformation_ch1_ARS408_can_database_ch1(&SpeedInformation_ch1,CAN_data,&CAN_DLC,&CAN_IDE);
-                this->Trans_to_CANRaw(xraw);
-                pBuffer->Produce_Element(xraw);
+                pBuffer->Produce_Element(Trans_to_CANRaw());
 
                 YawRateInformation_ch1.RadarDevice_YawRate_phys = gpsYawRate;
+                this->Clear_CAN_PrivateTempVariable();
                 CAN_ID = Pack_YawRateInformation_ch1_ARS408_can_database_ch1(&YawRateInformation_ch1,CAN_data,&CAN_DLC,&CAN_IDE);
-                this->Trans_to_CANRaw(xraw);
-                pBuffer->Produce_Element(xraw);
+                pBuffer->Produce_Element(Trans_to_CANRaw());
                 break;
             case 2:
                 SpeedInformation_ch2.RadarDevice_SpeedDirection = speedDirection;
                 SpeedInformation_ch2.RadarDevice_Speed_phys = speedFinal;
+                this->Clear_CAN_PrivateTempVariable();
                 CAN_ID = Pack_SpeedInformation_ch2_ARS408_can_database_ch2(&SpeedInformation_ch2,CAN_data,&CAN_DLC,&CAN_IDE);
-                this->Trans_to_CANRaw(xraw);
-                pBuffer->Produce_Element(xraw);
+                pBuffer->Produce_Element(Trans_to_CANRaw());
 
                 YawRateInformation_ch2.RadarDevice_YawRate_phys = gpsYawRate;
+                this->Clear_CAN_PrivateTempVariable();
                 CAN_ID = Pack_YawRateInformation_ch2_ARS408_can_database_ch2(&YawRateInformation_ch2,CAN_data,&CAN_DLC,&CAN_IDE);
-                this->Trans_to_CANRaw(xraw);
-                pBuffer->Produce_Element(xraw);
+                pBuffer->Produce_Element(Trans_to_CANRaw());
                 break;
             case 3:
                 SpeedInformation_ch3.RadarDevice_SpeedDirection = speedDirection;
                 SpeedInformation_ch3.RadarDevice_Speed_phys = speedFinal;
+                this->Clear_CAN_PrivateTempVariable();
                 CAN_ID = Pack_SpeedInformation_ch3_ARS408_can_database_ch3(&SpeedInformation_ch3,CAN_data,&CAN_DLC,&CAN_IDE);
-                this->Trans_to_CANRaw(xraw);
-                pBuffer->Produce_Element(xraw);
+                pBuffer->Produce_Element(Trans_to_CANRaw());
 
                 YawRateInformation_ch3.RadarDevice_YawRate_phys = gpsYawRate;
+                this->Clear_CAN_PrivateTempVariable();
                 CAN_ID = Pack_YawRateInformation_ch3_ARS408_can_database_ch3(&YawRateInformation_ch3,CAN_data,&CAN_DLC,&CAN_IDE);
-                this->Trans_to_CANRaw(xraw);
-                pBuffer->Produce_Element(xraw);
+                pBuffer->Produce_Element(Trans_to_CANRaw());
                 break;
             case 4:
                 SpeedInformation_ch4.RadarDevice_SpeedDirection = speedDirection;
                 SpeedInformation_ch4.RadarDevice_Speed_phys = speedFinal;
+                this->Clear_CAN_PrivateTempVariable();
                 CAN_ID = Pack_SpeedInformation_ch4_ARS408_can_database_ch4(&SpeedInformation_ch4,CAN_data,&CAN_DLC,&CAN_IDE);
-                this->Trans_to_CANRaw(xraw);
-                pBuffer->Produce_Element(xraw);
+                pBuffer->Produce_Element(Trans_to_CANRaw());
 
                 YawRateInformation_ch4.RadarDevice_YawRate_phys = gpsYawRate;
+                this->Clear_CAN_PrivateTempVariable();
                 CAN_ID = Pack_YawRateInformation_ch4_ARS408_can_database_ch4(&YawRateInformation_ch4,CAN_data,&CAN_DLC,&CAN_IDE);
-                this->Trans_to_CANRaw(xraw);
-                pBuffer->Produce_Element(xraw);
+                pBuffer->Produce_Element(Trans_to_CANRaw());
                 break;
             case 5:
                 SpeedInformation_ch5.RadarDevice_SpeedDirection = speedDirection;
                 SpeedInformation_ch5.RadarDevice_Speed_phys = speedFinal;
+                this->Clear_CAN_PrivateTempVariable();
                 CAN_ID = Pack_SpeedInformation_ch5_ARS408_can_database_ch5(&SpeedInformation_ch5,CAN_data,&CAN_DLC,&CAN_IDE);
-                this->Trans_to_CANRaw(xraw);
-                pBuffer->Produce_Element(xraw);
+                pBuffer->Produce_Element(Trans_to_CANRaw());
 
                 YawRateInformation_ch5.RadarDevice_YawRate_phys = gpsYawRate;
+                this->Clear_CAN_PrivateTempVariable();
                 CAN_ID = Pack_YawRateInformation_ch5_ARS408_can_database_ch5(&YawRateInformation_ch5,CAN_data,&CAN_DLC,&CAN_IDE);
-                this->Trans_to_CANRaw(xraw);
-                pBuffer->Produce_Element(xraw);
+                pBuffer->Produce_Element(Trans_to_CANRaw());
                 break;
             case 6:
                 SpeedInformation_ch6.RadarDevice_SpeedDirection = speedDirection;
                 SpeedInformation_ch6.RadarDevice_Speed_phys = speedFinal;
+                this->Clear_CAN_PrivateTempVariable();
                 CAN_ID = Pack_SpeedInformation_ch6_ARS408_can_database_ch6(&SpeedInformation_ch6,CAN_data,&CAN_DLC,&CAN_IDE);
-                this->Trans_to_CANRaw(xraw);
-                pBuffer->Produce_Element(xraw);
+                pBuffer->Produce_Element(Trans_to_CANRaw());
 
                 YawRateInformation_ch6.RadarDevice_YawRate_phys = gpsYawRate;
+                this->Clear_CAN_PrivateTempVariable();
                 CAN_ID = Pack_YawRateInformation_ch6_ARS408_can_database_ch6(&YawRateInformation_ch6,CAN_data,&CAN_DLC,&CAN_IDE);
-                this->Trans_to_CANRaw(xraw);
-                pBuffer->Produce_Element(xraw);
+                pBuffer->Produce_Element(Trans_to_CANRaw());
                 break;
             case 7:
                 SpeedInformation_ch7.RadarDevice_SpeedDirection = speedDirection;
                 SpeedInformation_ch7.RadarDevice_Speed_phys = speedFinal;
+                this->Clear_CAN_PrivateTempVariable();
                 CAN_ID = Pack_SpeedInformation_ch7_ARS408_can_database_ch7(&SpeedInformation_ch7,CAN_data,&CAN_DLC,&CAN_IDE);
-                this->Trans_to_CANRaw(xraw);
-                pBuffer->Produce_Element(xraw);
+                pBuffer->Produce_Element(Trans_to_CANRaw());
 
                 YawRateInformation_ch7.RadarDevice_YawRate_phys = gpsYawRate;
+                this->Clear_CAN_PrivateTempVariable();
                 CAN_ID = Pack_YawRateInformation_ch7_ARS408_can_database_ch7(&YawRateInformation_ch7,CAN_data,&CAN_DLC,&CAN_IDE);
-                this->Trans_to_CANRaw(xraw);
-                pBuffer->Produce_Element(xraw);
+                pBuffer->Produce_Element(Trans_to_CANRaw());
                 break;
             default:
                 break;

+ 4 - 2
src/driver/driver_radar_continental_ARS408_SRR308/cansend_producer.h

@@ -7,7 +7,9 @@
 #include <QThread>
 
 #include "modulecomm.h"
+
 #include "can_producer_consumer.h"
+#include "decode_cfg.h"
 
 class CANSend_Producer : public QThread
 {
@@ -15,11 +17,11 @@ class CANSend_Producer : public QThread
 public:
     CANSend_Producer(CAN_Producer_Consumer *pBuf);
     ~CANSend_Producer();
-
-    uint32_t Trans_to_CANRaw(iv::can::canraw &xraw); //return CAN_ID
+    void Clear_CAN_PrivateTempVariable(void);
 
 protected:
     void run();
+    iv::can::canraw Trans_to_CANRaw(void);
 
 private:
     CAN_Producer_Consumer *pBuffer;

+ 1 - 0
src/driver/driver_radar_continental_ARS408_SRR308/main.cpp

@@ -28,6 +28,7 @@
 /*
  * Notice : the radar config setting function is not finished
  * Notice : the number of object is less than 64. so this version is used for object mode.
+ * Notice : only can decode standard data CAN frame
 */
 
 QCoreApplication * gApp;