Explorar o código

增加了4D雷达发送频率,增加了莫之比多点雷达

redaiyuyuyu hai 1 mes
pai
achega
d576e980e9

+ 2 - 1
.vscode/settings.json

@@ -9,5 +9,6 @@
     },
     "RTT_Studio.Build.Parallel_Jobs": "16",
     "C_Cpp.default.configurationProvider": "ms-vscode.cmake-tools",
-    "cortex-debug.variableUseNaturalFormat": true
+    "cortex-debug.variableUseNaturalFormat": true,
+    "makefile.configureOnOpen": true
 }

+ 9 - 0
Inc/soft_can.h

@@ -68,6 +68,15 @@ extern Radar Rupdate;
 #define CAN_MIMO_BOBS_ID1 (0x411)
 #define CAN_MIMO_BOBS_ID2 (0x412)
 #define CAN_MIMO_BOBS_ID3 (0x413)
+//莫之比前避障(多点)
+#define CAN_UAVRH_FOBS_ID1 (0x601)
+#define CAN_UAVRH_FOBS_ID2 (0x602)
+#define CAN_UAVRH_FOBS_ID3 (0x603)
+//莫之比后避障(多点)
+#define CAN_UAVRH_BOBS_ID1 (0x611)
+#define CAN_UAVRH_BOBS_ID2 (0x612)
+#define CAN_UAVRH_BOBS_ID3 (0x613)
+
 //恩曌前避障(单点)
 #define CAN_MIMO_FOBS_SIG (0x301)
 //恩曌后避障(单点)

+ 2 - 1
Inc/soft_obstacle.h

@@ -166,7 +166,8 @@ bool check_radar_update(void);
 void can_recv_mocib_new360_obstacle(uint32_t cellCanID, uint8_t data[], uint8_t len);
 void can_recv_mimo_signal_obstacle(uint32_t cellCanID, uint8_t data[], uint8_t len);
 void can_recv_mimo_radar_version(uint32_t cellCanID, uint8_t data[], uint8_t len);
-void mimo_buf_sort(mimo_part_radar *arr, uint16_t length);
+void mimomocib_buf_sort(mimo_part_radar *arr, uint16_t length);
 void get_radar_blindAndPower_function( void );
+void can_recv_mocib_obstacle(uint32_t cellCanID, uint8_t data[], uint8_t len);
 #endif 
 

+ 2 - 1
Inc/soft_seed_device.h

@@ -362,7 +362,8 @@ typedef struct
 
     _Temp_sensor Temp_sensor;
     Connect_check Temp_Sensor_Link;
-
+		
+    Connect_check Part_Bradar_Link;
 } Device_type;
 extern Device_type Dev;
 

+ 1 - 0
Inc/soft_terrain.h

@@ -131,6 +131,7 @@ extern Connect_check DM_4dstatus;
 extern DM_RADAR DM_T_info,FMU_DM_info;
 extern uint8_t DM_recv_flag;
 extern uint8_t DM4d_recv_flag;
+extern uint8_t DM4d_to_fmu_flag;
 void DM_terrain_recieved_hookfuction(uint32_t cellCanID,uint8_t data[], uint8_t len);
 void DM_Fobs_recieved_hookfuction(uint32_t cellCanID,uint8_t data[], uint8_t len);
 #endif 

+ 2 - 2
Src/common.c

@@ -60,8 +60,8 @@ void u16t_buf_sort( uint16_t *arr, uint16_t length )
     }
 }
 
-/*****************************恩曌雷达排序************************/
-void mimo_buf_sort( mimo_part_radar *arr, uint16_t length )
+/*****************************恩曌&莫之比雷达排序************************/
+void mimomocib_buf_sort( mimo_part_radar *arr, uint16_t length )
 {
     if ( length < 2 )
     {

+ 2 - 6
Src/soft_bms.c

@@ -291,7 +291,7 @@ void update_bms_data( void )
         Dev.Bms_Link.connect_status = COMP_NORMAL;
         group_num = 1;
 
-        bms_data.bms_cycle = herewin_info.circulation_num;
+        bms_data.bms_cycle = herewin_info.circulation_num;//海盈电池循环次数
         bms_data.bms_volt = herewin_info.total_vol;
         
         if(herewin_info.get_temp_flag == true)
@@ -980,10 +980,6 @@ void BMSCanRecvHookFunction(uint32_t CanID, uint8_t data[], uint8_t len)
     {
         if(Bmspointer->mul_frame_num == frame_num /*&& ((Bmspointer->mul_frame_i + len) <= sizeof(vkbms2))*/ )
         {
-            if(msg_id == 0x03)
-            {
-                msg_id = 0x03;
-            }
             memcpy(&Bmspointer->bms_can_buf[Bmspointer->mul_frame_i],&data[0],len);
 
             Bmspointer->mul_frame_i += len;
@@ -1030,7 +1026,7 @@ void BMSCanRecvHookFunction(uint32_t CanID, uint8_t data[], uint8_t len)
     case 0X02:
         if(Bmspointer->recv_mul_freme_complete == true)
         {   
-            memcpy(&Bmspointer->vk_bms2.voltage, &Bmspointer->bms_can_buf[2], sizeof(vkbms2));
+            memcpy(&Bmspointer->vk_bms2.voltage, &Bmspointer->bms_can_buf[2], sizeof(vkbms2));//接收一整包电池数据
             Bmspointer->recv_mul_freme_complete = false;
         }
         break; 

+ 6 - 3
Src/soft_can.c

@@ -104,7 +104,10 @@ void Can_decode_data_function(CAN_RxHeaderTypeDef Rxhead)
       case GEELY_ENGINE_START_ID2 ... GEELY_ENGINE_END_ID2:
         EngGeelyCanRecvHookFunction(RxHeader.StdId, RxData, RxHeader.DLC);
         break;  
-
+      //莫之比前后避障雷达(多点)
+      case CAN_UAVRH_FOBS_ID1 ... CAN_UAVRH_BOBS_ID3: 
+        can_recv_mocib_obstacle(RxHeader.StdId, RxData, RxHeader.DLC);
+        break;
       case CAN_EZ_R_UPDATE:
         EZ_Radar_UpdateCanRecvHookFunction(RxHeader.StdId, RxData, RxHeader.DLC);
         break;
@@ -391,11 +394,11 @@ void HAL_CAN_RxFifo0MsgPendingCallback(CAN_HandleTypeDef *hcan)
       Weight_recieved_hookfuction(RxHeader.ExtId, RxData, RxHeader.DLC);
       break; 
     //VK设备升级
-    case CAN_NODEID_RADAR_UPDATE:
+    case CAN_NODEID_RADAR_UPDATE://14
         switch (((RxHeader.ExtId) & MSG_ID_MASK) >> 19)
         {
         case CAN_MSGID_RADAR_START:
-          if((RxHeader.ExtId & 0x3) == 1)
+          if((RxHeader.ExtId & 0x3) == 1)//381401
           {
             uart_info.step_200_flag = true;
           }

+ 2 - 2
Src/soft_eft.c

@@ -330,10 +330,10 @@ void DMlacklossCanRecvFunction(uint32_t cellCanID, uint8_t data[], uint8_t len)/
         DM_lackloss.status = 1;
         break;
     case 0XB0:
-        pmu_set_ack(_MSGID_SET,MSGID_SET_LACKLOSS_CAL,0x01,0x00);
+        pmu_set_ack(_MSGID_SET,MSGID_SET_LACKLOSS_CAL,0x01,0x00);//成功
         break;
     case 0XB1 ... 0XB2:
-        pmu_set_ack(_MSGID_SET,MSGID_SET_LACKLOSS_CAL,0x02,0x00);
+        pmu_set_ack(_MSGID_SET,MSGID_SET_LACKLOSS_CAL,0x02,0x00);//失败
         break;
     default:
         break;

+ 1 - 1
Src/soft_herewin.c

@@ -24,7 +24,7 @@ typedef struct
 
 herewin_can_info can_info;
 
-void HerewinCanRecvHookFunction(uint32_t cellCanID, uint8_t data[], uint8_t len)
+void HerewinCanRecvHookFunction(uint32_t cellCanID, uint8_t data[], uint8_t len)//海盈
 {
 
     Herewin_Link.recv_time = HAL_GetTick();

+ 95 - 3
Src/soft_obstacle.c

@@ -70,7 +70,7 @@ void can_recv_enzhao_obstacle(uint32_t cellCanID, uint8_t data[], uint8_t len)
     if(recv_comF_flag == 7)
     {
         recv_comF_flag = 0;      
-        mimo_buf_sort(&F_radar[0], 3);
+        mimomocib_buf_sort(&F_radar[0], 3);
 
         for (uint8_t i = 0; i < 3; i++)
         {
@@ -94,7 +94,7 @@ void can_recv_enzhao_obstacle(uint32_t cellCanID, uint8_t data[], uint8_t len)
     if(recv_comB_flag == 7)
     {
         recv_comB_flag = 0;
-        mimo_buf_sort(&B_radar[0], 3);
+        mimomocib_buf_sort(&B_radar[0], 3);
 
         for (uint8_t i = 0; i < 3; i++)
         {
@@ -592,7 +592,99 @@ void can_recv_mocib_B_obstacle(uint8_t *data)
     uavr12_info.Link.connect_status = COMP_NORMAL;
     uavr12_info.Link.recv_time = HAL_GetTick();
 }
+/**
+  * @file    can_recv_mocib_obstacle
+  * @brief   莫之比避障解析(多点)
+  * @param   none
+  * @details 
+  * @author  biao 
+ **/
+void can_recv_mocib_obstacle(uint32_t cellCanID, uint8_t data[], uint8_t len)
+{
+    switch (cellCanID)
+    {
+    case CAN_UAVRH_FOBS_ID1:
+        memcpy(&F_radar[0], data, 8);
+        recv_comF_flag = recv_comF_flag | 1;
+        Dev.Radar.facid_F = FAC_MOCIB_RF;
+        Dev.Part_Fradar_Link.connect_status = COMP_NORMAL;
+        Dev.Part_Fradar_Link.recv_time = HAL_GetTick();
+        break;
+    case CAN_UAVRH_FOBS_ID2:
+        memcpy(&F_radar[1], data, 8);
+        recv_comF_flag = recv_comF_flag | 2;
+        break;
+    case CAN_UAVRH_FOBS_ID3:
+        memcpy(&F_radar[2], data, 8);
+        recv_comF_flag = recv_comF_flag | 4;
+        break;
+    case CAN_UAVRH_BOBS_ID1:
+        memcpy(&B_radar[0], data, 8);
+        recv_comB_flag = recv_comB_flag | 1;
+        Dev.Radar.facid_B= FAC_MOCIB_RB;
+        Dev.Part_Bradar_Link.connect_status = COMP_NORMAL;
+        Dev.Part_Bradar_Link.recv_time = HAL_GetTick();
+        break;
+    case CAN_UAVRH_BOBS_ID2:
+        memcpy(&B_radar[1], data, 8);
+        recv_comB_flag = recv_comB_flag | 2;
+        break;
+    case CAN_UAVRH_BOBS_ID3:
+        memcpy(&B_radar[2], data, 8);
+        recv_comB_flag = recv_comB_flag | 4;
+        break;
+    default:
+        break;
+    }
+
+    if(recv_comF_flag == 7)
+    {
+        recv_comF_flag = 0;      
+        mimomocib_buf_sort(&F_radar[0], 3);
 
+        for (uint8_t i = 0; i < 3; i++)
+        {
+            //X轴小于4M内数据
+            if (/*(abs(F_radar[i].Distance * 0.05f * 100 * sin(F_radar[i].Amuzith * 0.1f / RAD)) < 400) &&*/ F_radar[i].Distance > 0)
+            {
+                uavr11_info.distance_x  = F_radar[i].Distance * 0.05f * 100 * sin(F_radar[i].Amuzith * 0.1f / RAD);
+                uavr11_info.distance_y = F_radar[i].Distance * 0.05f * 100 * cos(F_radar[i].Amuzith * 0.1f / RAD);
+                break;
+            }
+            if(i == 2)
+            {
+                uavr11_info.distance_x = 0;
+                uavr11_info.distance_y = 0;
+            }
+        }
+        uavr11_info.Link.connect_status = COMP_NORMAL;
+        uavr11_info.Link.recv_time = HAL_GetTick();
+    }
+    
+    if(recv_comB_flag == 7)
+    {
+        recv_comB_flag = 0;
+        mimomocib_buf_sort(&B_radar[0], 3);
+
+        for (uint8_t i = 0; i < 3; i++)
+        {
+            //X轴小于4M内数据
+            if (/*(abs(B_radar[i].Distance * 0.05f * 100 * sin(B_radar[i].Amuzith * 0.1f / RAD)) < 400) &&*/ B_radar[i].Distance > 0)
+            {
+                uavr12_info.distance_x  = B_radar[i].Distance * 0.05f * 100 * sin(B_radar[i].Amuzith * 0.1f / RAD);
+                uavr12_info.distance_y = B_radar[i].Distance * 0.05f * 100 * cos(B_radar[i].Amuzith * 0.1f / RAD);
+                break; 
+            }
+            if(i == 2)
+            {
+                uavr12_info.distance_x = 0;
+                uavr12_info.distance_y = 0;
+            }
+        }
+        uavr12_info.Link.recv_time = HAL_GetTick();
+        uavr12_info.Link.connect_status = COMP_NORMAL;
+    }
+}
 uint32_t uavr20_ver_time = 0;
 
 uint32_t uavr20_sensi_time = 0;
@@ -1058,7 +1150,7 @@ void can_send_info_to_mimo()
     static int mimo_50HZ = 0;
     static int mimo_49HZ = 0;
     if (mimo_f_info.Link.connect_status == COMP_NORMAL || mimo_b_info.Link.connect_status == COMP_NORMAL /*|| 
-        mimo_360_info.connect_status == COMP_NORMAL*/ || Dev.Part_Fradar_Link.connect_status == COMP_NORMAL)
+        mimo_360_info.connect_status == COMP_NORMAL*/ || (Dev.Part_Fradar_Link.connect_status == COMP_NORMAL && Dev.Part_radarF.facid == FAC_MIMO_RF))
     {
         int16_t index = 0;
         short tmpShort = 0;

+ 3 - 2
Src/soft_p_2_c.c

@@ -38,7 +38,6 @@
 
 uint8_t msg_buf[256] = {0};
 uint16_t crc = 0;
-uint32_t DMJZ=0;
 pmu_data pmu;
 plane_para planep = {.Candebug_flag = 0};
 
@@ -545,7 +544,7 @@ void pmu_to_con_DMradar_data(void)
         uart2_send_msg(msg_buf, index);
     }
     
-    if(DM_4dstatus.connect_status == COMP_NORMAL)
+    if(DM_4dstatus.connect_status == COMP_NORMAL && DM4d_to_fmu_flag == 1)
     {
         int8_t pack_count = 0;//需要发送包数
         int8_t remain_lastcount = 0; //余数
@@ -605,6 +604,7 @@ void pmu_to_con_DMradar_data(void)
             send_pack++;
         }
         DM4d_recv_flag = 0;
+        DM4d_to_fmu_flag = 0;
     }
 }
 
@@ -1283,6 +1283,7 @@ void check_fmu_link()
 _pmu_pin pmu_pin;
 bool recv_fmu_data = false;
 Set_info msgidset;
+uint32_t DMJZ = 0 ;
 void uart_recv_con_msg()
 {
     check_fmu_link();

+ 1 - 1
Src/soft_seed_device.c

@@ -639,7 +639,7 @@ void check_dev_type_link(void )
 
 void DM_obs_test( void )
 {
-    if(Dev.Part_Fradar_Link.connect_status != COMP_NORMAL)
+    if((Dev.Part_Fradar_Link.connect_status != COMP_NORMAL) || (Dev.Part_radarF.facid != FAC_DM_RF))
         return;
 
     static uint32_t time_50hz = 0;

+ 39 - 30
Src/soft_terrain.c

@@ -106,6 +106,7 @@ uint8_t DM4d_recv_flag = 0;
 Connect_check DM_status;
 Connect_check DM_4dstatus;
 uavr_terrain DM_ter_info; 
+uint8_t DM4d_to_fmu_flag = 0;
 void DM_terrain_recieved_hookfuction(uint32_t cellCanID,uint8_t data[], uint8_t len)
 {
     if(cellCanID == 0x901300) //多点协议
@@ -222,45 +223,45 @@ int dm_4df_i = 0;
 DM_4DRADAR FMU_4D_info;
 void DM_Fobs_recieved_hookfuction(uint32_t cellCanID,uint8_t data[], uint8_t len)
 {
-    if(cellCanID == 0XA01300) //多点协议
+    if (cellCanID == 0XA01300) // 多点协议
     {
         DM_T_info.byte7.frame_flag = data[7];
 
         DM_status.connect_status = COMP_NORMAL;
         DM_status.recv_time = HAL_GetTick();
-        
-        if(DM_T_info.byte7.flag.head != 0 ) //头
+
+        if (DM_T_info.byte7.flag.head != 0) // 
         {
-            memcpy(&DM_T_info.target_num,&data[0],7);
+            memcpy(&DM_T_info.target_num, &data[0], 7);
             dm_i = 0;
-            if(DM_T_info.target_num == 0 && DM_recv_flag == 0)
+            if (DM_T_info.target_num == 0 && DM_recv_flag == 0)
             {
                 FMU_DM_info.target_num = 0;
             }
         }
-        else if(DM_T_info.byte7.flag.tail != 0) //尾
+        else if (DM_T_info.byte7.flag.tail != 0) // 
         {
-            if(DM_T_info.target_num != 1)
+            if (DM_T_info.target_num != 1)
             {
-                memcpy(&DM_T_info.buf[dm_i],&data[0],DM_T_info.target_num*4%7);
+                memcpy(&DM_T_info.buf[dm_i], &data[0], DM_T_info.target_num * 4 % 7);
             }
             else
             {
-                memcpy(&DM_T_info.buf[dm_i],&data[0],4);
+                memcpy(&DM_T_info.buf[dm_i], &data[0], 4);
             }
 
-            if(DM_T_info.crc == Get_Crc16(&DM_T_info.buf[0],DM_T_info.target_num * 4) &&  DM_recv_flag == 0)
+            if (DM_T_info.crc == Get_Crc16(&DM_T_info.buf[0], DM_T_info.target_num * 4) && DM_recv_flag == 0)
             {
-                memcpy(&FMU_DM_info.target_num,&DM_T_info.target_num,DM_T_info.target_num * 4 + 8);
-                //memcpy(&FMU_DM_info.buf[0], &DM_T_info.buf[0], DM_T_info.target_num * 4);
+                memcpy(&FMU_DM_info.target_num, &DM_T_info.target_num, DM_T_info.target_num * 4 + 8);
+                // memcpy(&FMU_DM_info.buf[0], &DM_T_info.buf[0], DM_T_info.target_num * 4);
             }
         }
         else
         {
-            memcpy(&DM_T_info.buf[dm_i],&data[0],7);
+            memcpy(&DM_T_info.buf[dm_i], &data[0], 7);
             dm_i += 7;
         }
-        if(dm_i >= 255 -7)
+        if (dm_i >= 255 - 7)
         {
             dm_i = 0;
         }
@@ -274,49 +275,57 @@ void DM_Fobs_recieved_hookfuction(uint32_t cellCanID,uint8_t data[], uint8_t len
         DM_f_info.distance_y = data[3] + data[4] * 256;
     }
 
-    //4D前避障雷达协议 点云
-    if(cellCanID == 0XA01310)
+    // 4D前避障雷达协议 点云
+    if (cellCanID == 0XA01310)
     {
         DM_4dstatus.connect_status = COMP_NORMAL;
         DM_status.recv_time = HAL_GetTick();
         Dev.Part_radarF.facid = FAC_DM_RF;
 
         DM_F4d.byte7.frame_flag = data[7];
-        
-        if(DM_F4d.byte7.flag.head!= 0 ) //头
+
+        if (DM_F4d.byte7.flag.head != 0) // 
         {
-            memcpy(&DM_F4d.target_num,&data[0],7);
+            memcpy(&DM_F4d.target_num, &data[0], 7);
             dm_4df_i = 0;
         }
-        else if(DM_F4d.byte7.flag.tail != 0) //尾
+        else if (DM_F4d.byte7.flag.tail != 0) // 
         {
-            if(DM_F4d.target_num != 1)
+            if (DM_F4d.target_num != 1)
             {
-                memcpy(&DM_F4d.RawData[dm_4df_i],&data[0],(DM_F4d.target_num * 5) % 7);
+                if ((DM_F4d.target_num * 5) % 7 != 0)
+                {
+                    memcpy(&DM_F4d.RawData[dm_4df_i], &data[0], (DM_F4d.target_num * 5) % 7);
+                    dm_4df_i += (DM_F4d.target_num * 5) % 7;
+                }
+                else
+                {
+                    memcpy(&DM_F4d.RawData[dm_4df_i], &data[0], 7);
+                    dm_4df_i += 7;
+                }
             }
             else
             {
-                memcpy(&DM_F4d.RawData[dm_4df_i],&data[0],5);
+                memcpy(&DM_F4d.RawData[dm_4df_i], &data[0], 5);
+                dm_4df_i += 5;
             }
-
-            if(DM_F4d.crc == Get_Crc16(&DM_F4d.RawData[0],DM_F4d.target_num * 5) &&  DM4d_recv_flag == 0)
+            if (DM_F4d.crc == Get_Crc16(&DM_F4d.RawData[0], DM_F4d.target_num * 5) && DM4d_recv_flag == 0)
             {
                 FMU_4D_info.target_num = DM_F4d.target_num;
-                memcpy(&FMU_4D_info.buf,&DM_F4d.RawData,DM_F4d.target_num *5);
+                memcpy(&FMU_4D_info.buf, &DM_F4d.RawData, DM_F4d.target_num * 5);
+                DM4d_to_fmu_flag = 1;
             }
         }
         else
         {
-            memcpy(&DM_F4d.RawData[dm_4df_i],&data[0],7);
+            memcpy(&DM_F4d.RawData[dm_4df_i], &data[0], 7);
             dm_4df_i += 7;
         }
-        if(dm_4df_i >= 254 * 5)
+        if (dm_4df_i >= 254 * 5)
         {
             dm_4df_i = 0;
         }
     }
-
-    
     //4D前避障雷达协议 单点
     if(cellCanID == 0XA01302)
     {

+ 4 - 2
Src/soft_uart.c

@@ -26,6 +26,7 @@
 #include "common.h"
 #include "soft_water_device.h"
 #include "config.h"
+#include "soft_seed_device.h"
 
 uint8_t Update_buf[150] = {0};
 
@@ -417,9 +418,10 @@ void check_uart_data(rkfifo_t *fifo)
 					uart_info.fcu_buf_flag = true; 
 				}
 				//莫之比雷达升级
-				else if((vk_data.group_id == GROUP_ID_F_UPDATE && uavr11_info.Link.connect_status != COMP_NOEXIST) ||
+				else if(((vk_data.group_id == GROUP_ID_F_UPDATE && uavr11_info.Link.connect_status != COMP_NOEXIST) ||
 					 	(vk_data.group_id == GROUP_ID_B_UPDATE && uavr12_info.Link.connect_status != COMP_NOEXIST) ||
-					    (vk_data.group_id == GROUP_ID_T_UPDATE && uavr56_info.Link.connect_status != COMP_NOEXIST))
+					    (vk_data.group_id == GROUP_ID_T_UPDATE && uavr56_info.Link.connect_status != COMP_NOEXIST)) && 
+						(Dev.Part_Bradar_Link.connect_status == COMP_NOEXIST && Dev.Part_Fradar_Link.connect_status == COMP_NOEXIST))
 				{	
 					if(uart_info.use_update_buf_flag == false)
 					{

+ 22 - 1
Src/soft_update.c

@@ -86,6 +86,10 @@ void Vk_Update_Device_Protocol(void)
             {
                 memcpy(&can_buf[5],"DW1",3);
             }
+            else if(Dev.Radar.facid_F == FAC_MOCIB_RF)
+            {
+                memcpy(&can_buf[5],"MZB",3);
+            }
             else if(Dev.Part_radarF.facid == FAC_DM_RF)
             {
                 memcpy(&can_buf[5],"D4F",3);
@@ -96,6 +100,10 @@ void Vk_Update_Device_Protocol(void)
             {
                 memcpy(&can_buf[5],"TR0",3);
             }
+            else if(Dev.Radar.facid_B == FAC_MOCIB_RB)
+            {
+                memcpy(&can_buf[5],"MZB",3);
+            }
             break;
         case UPDATE_TERAIN:
             if(Dev.Radar.facid_T == FAC_MIMO_RT)
@@ -192,7 +200,6 @@ void Update_Dev_Bootversion_Function(uint8_t data[])
         case UPDATE_OBS_F:
             if(memcmp((char *)&data[1],"TR0",3) == 0)
             {
-                mimo_f_info.Link.connect_status = COMP_NORMAL;
                 mimo_f_info.Link.recv_time = HAL_GetTick();
                 mimo_f_info.Link.boot_flag = true;
                 Dev.Radar.facid_F = FAC_MIMO_RF;
@@ -213,6 +220,13 @@ void Update_Dev_Bootversion_Function(uint8_t data[])
                 }
 				regist_dev_info(&dev_obsf,DEVICE_OBSF,false,NULL,0,DM_f_info.version,10,NULL,0,"dmf",6);
             }
+            else if(memcmp((char *)&data[1],"MZB",3) == 0)
+            {
+                Dev.Part_Fradar_Link.recv_time = HAL_GetTick();
+                Dev.Part_Fradar_Link.connect_status= COMP_NORMAL;
+                Dev.Part_Fradar_Link.boot_flag = true;
+                Dev.Radar.facid_F=FAC_MOCIB_RF;
+            }
             else if(memcmp((char *)&data[1],"D4F",3) == 0)
             {
                 Dev.Part_Fradar_Link.recv_time = HAL_GetTick();
@@ -245,6 +259,13 @@ void Update_Dev_Bootversion_Function(uint8_t data[])
                 mimo_b_info.Link.boot_flag = true;
                 Dev.Radar.facid_B = FAC_MIMO_RB;
             }
+            else if(memcmp((char *)&data[1],"MZB",3) == 0)
+            {
+                Dev.Part_Bradar_Link.recv_time = HAL_GetTick();
+                Dev.Part_Bradar_Link.connect_status= COMP_NORMAL;
+                Dev.Part_Bradar_Link.boot_flag = true;
+                Dev.Radar.facid_B = FAC_MOCIB_RB;
+            }
             else if(memcmp((char *)&data[1],"D4B",3) == 0)
             {
                 // Dev.Part_Tradar_Link.recv_time = HAL_GetTick();