soft_obstacle.c 55 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111111211131114111511161117111811191120112111221123112411251126112711281129113011311132113311341135113611371138113911401141114211431144114511461147114811491150115111521153115411551156115711581159116011611162116311641165116611671168116911701171117211731174117511761177117811791180118111821183118411851186118711881189119011911192119311941195119611971198119912001201120212031204120512061207120812091210121112121213121412151216121712181219122012211222122312241225122612271228122912301231123212331234123512361237123812391240124112421243124412451246124712481249125012511252125312541255125612571258125912601261126212631264126512661267126812691270127112721273127412751276127712781279128012811282128312841285128612871288128912901291129212931294129512961297129812991300130113021303130413051306130713081309131013111312131313141315131613171318131913201321132213231324132513261327132813291330133113321333133413351336133713381339134013411342134313441345134613471348134913501351135213531354135513561357135813591360136113621363136413651366136713681369137013711372137313741375137613771378137913801381138213831384138513861387138813891390139113921393139413951396139713981399140014011402140314041405140614071408140914101411141214131414141514161417141814191420142114221423142414251426142714281429143014311432143314341435143614371438143914401441144214431444144514461447144814491450145114521453145414551456145714581459146014611462146314641465146614671468146914701471147214731474147514761477147814791480148114821483148414851486148714881489149014911492149314941495149614971498149915001501150215031504150515061507150815091510151115121513151415151516151715181519152015211522152315241525152615271528152915301531153215331534153515361537153815391540154115421543154415451546154715481549155015511552155315541555155615571558155915601561156215631564156515661567156815691570157115721573157415751576157715781579158015811582158315841585158615871588158915901591159215931594159515961597159815991600
  1. #include "soft_obstacle.h"
  2. #include "tim.h"
  3. #include "string.h"
  4. #include "math.h"
  5. #include "soft_terrain.h"
  6. #include "soft_uart.h"
  7. #include "common.h"
  8. #include "soft_can.h"
  9. #include "soft_p_2_c.h"
  10. #include "stdlib.h"
  11. #include "soft_flow.h"
  12. #include "common.h"
  13. #include "soft_seed_device.h"
  14. #include "soft_water_device.h"
  15. #include "soft_version.h"
  16. #include "soft_eft.h"
  17. #include "common.h"
  18. uavr_obs uavr11_info = {.get_radar_sensi = 50};
  19. uavr_obs uavr12_info= {.get_radar_sensi = 50};
  20. uavr_obs uavr13_info= {.get_radar_sensi = 50};
  21. uavr_obs uavr14_info= {.get_radar_sensi = 50};
  22. uavr_obs mimo_f_info = {.signal_qulity = 0};
  23. uavr_obs mimo_b_info = {.signal_qulity = 0};
  24. uavr_obs DM_f_info;
  25. DM_4D_REDARVER DM_4DB_info;
  26. /**
  27. * @file can_recv_enzhao_obstacle
  28. * @brief 恩曌多点避障解析
  29. * @param none
  30. * @details
  31. * @author Zhang Sir
  32. **/
  33. mimo_part_radar F_radar[3];
  34. mimo_part_radar B_radar[3];
  35. uint8_t recv_comF_flag = 0,recv_comB_flag = 0;
  36. void can_recv_enzhao_obstacle(uint32_t cellCanID, uint8_t data[], uint8_t len)
  37. {
  38. switch (cellCanID)
  39. {
  40. case CAN_MIMO_FOBS_ID1:
  41. memcpy(&F_radar[0], data, 8);
  42. recv_comF_flag = recv_comF_flag | 1;
  43. Dev.Radar.facid_F = FAC_MIMO_RF;
  44. break;
  45. case CAN_MIMO_FOBS_ID2:
  46. memcpy(&F_radar[1], data, 8);
  47. recv_comF_flag = recv_comF_flag | 2;
  48. break;
  49. case CAN_MIMO_FOBS_ID3:
  50. memcpy(&F_radar[2], data, 8);
  51. recv_comF_flag = recv_comF_flag | 4;
  52. break;
  53. case CAN_MIMO_BOBS_ID1:
  54. memcpy(&B_radar[0], data, 8);
  55. recv_comB_flag = recv_comB_flag | 1;
  56. Dev.Radar.facid_B = FAC_MIMO_RB;
  57. break;
  58. case CAN_MIMO_BOBS_ID2:
  59. memcpy(&B_radar[1], data, 8);
  60. recv_comB_flag = recv_comB_flag | 2;
  61. break;
  62. case CAN_MIMO_BOBS_ID3:
  63. memcpy(&B_radar[2], data, 8);
  64. recv_comB_flag = recv_comB_flag | 4;
  65. break;
  66. default:
  67. break;
  68. }
  69. if(recv_comF_flag == 7)
  70. {
  71. recv_comF_flag = 0;
  72. mimomocib_buf_sort(&F_radar[0], 3);
  73. for (uint8_t i = 0; i < 3; i++)
  74. {
  75. //X轴小于4M内数据
  76. if (/*(abs(F_radar[i].Distance * 0.05f * 100 * sin(F_radar[i].Amuzith * 0.1f / RAD)) < 400) &&*/ F_radar[i].Distance > 0)
  77. {
  78. mimo_f_info.distance_x = F_radar[i].Distance * 0.05f * 100 * sin(F_radar[i].Amuzith * 0.1f / RAD);
  79. mimo_f_info.distance_y = F_radar[i].Distance * 0.05f * 100 * cos(F_radar[i].Amuzith * 0.1f / RAD);
  80. break;
  81. }
  82. if(i == 2)
  83. {
  84. mimo_f_info.distance_x = 0;
  85. mimo_f_info.distance_y = 0;
  86. }
  87. }
  88. mimo_f_info.Link.connect_status = COMP_NORMAL;
  89. mimo_f_info.Link.recv_time = HAL_GetTick();
  90. }
  91. if(recv_comB_flag == 7)
  92. {
  93. recv_comB_flag = 0;
  94. mimomocib_buf_sort(&B_radar[0], 3);
  95. for (uint8_t i = 0; i < 3; i++)
  96. {
  97. //X轴小于4M内数据
  98. if (/*(abs(B_radar[i].Distance * 0.05f * 100 * sin(B_radar[i].Amuzith * 0.1f / RAD)) < 400) &&*/ B_radar[i].Distance > 0)
  99. {
  100. mimo_b_info.distance_x = B_radar[i].Distance * 0.05f * 100 * sin(B_radar[i].Amuzith * 0.1f / RAD);
  101. mimo_b_info.distance_y = B_radar[i].Distance * 0.05f * 100 * cos(B_radar[i].Amuzith * 0.1f / RAD);
  102. break;
  103. }
  104. if(i == 2)
  105. {
  106. mimo_b_info.distance_x = 0;
  107. mimo_b_info.distance_y = 0;
  108. }
  109. }
  110. mimo_b_info.Link.recv_time = HAL_GetTick();
  111. mimo_b_info.Link.connect_status = COMP_NORMAL;
  112. }
  113. }
  114. /**
  115. * @file can_recv_enzhao_obstacle
  116. * @brief 恩曌单避障解析
  117. * @param none
  118. * @details
  119. * @author Zhang Sir
  120. **/
  121. void can_recv_mimo_signal_obstacle(uint32_t cellCanID, uint8_t data[], uint8_t len)
  122. {
  123. uint16_t frame_header = 0;
  124. memcpy(&frame_header,&data[0],2);
  125. if(frame_header == 0x5AA5 && data[2] == 0x04)
  126. {
  127. switch (cellCanID)
  128. {
  129. case CAN_MIMO_FOBS_SIG:
  130. mimo_f_info.distance_y = data[3] + data[4] * 256;
  131. mimo_f_info.signal_qulity = data[5];
  132. mimo_f_info.Link.recv_time = HAL_GetTick();
  133. mimo_f_info.Link.connect_status = COMP_NORMAL;
  134. Dev.Radar.facid_F = FAC_MIMO_RF;
  135. break;
  136. case CAN_MIMO_BOBS_SIG:
  137. mimo_b_info.distance_y = data[3] + data[4] * 256;
  138. mimo_b_info.signal_qulity = data[5];
  139. mimo_b_info.Link.recv_time = HAL_GetTick();
  140. mimo_b_info.Link.connect_status = COMP_NORMAL;
  141. Dev.Radar.facid_B = FAC_MIMO_RB;
  142. break;
  143. default:
  144. break;
  145. }
  146. }
  147. }
  148. /**
  149. * @file can_recv_mimo_radar_version
  150. * @brief 恩曌设备版本获取
  151. * @param none
  152. * @details
  153. * @author Zhang Sir
  154. **/
  155. void can_recv_mimo_radar_version(uint32_t cellCanID, uint8_t data[], uint8_t len)
  156. {
  157. static uint8_t mimo_version[28] = {0};
  158. static uint8_t frame_num = 0;
  159. static bool frame_head = false;
  160. uint8_t i = 0;
  161. uint32_t checksum = 0;
  162. uint32_t soft_ver = 0;
  163. switch (cellCanID)
  164. {
  165. case 0XFB:
  166. if(data[0] == 0XAA && data[1] == 0X55)
  167. {
  168. if(data[2] == 0X03 && data[3] == 0X61 && data[4] == 0X03 && data[5] == 0X01 && data[6] == 0X65)
  169. {
  170. pmu_set_ack(_MSGID_SET,MSGID_SET_RADAR_FB,0x11,0);
  171. }
  172. else if(data[2] == 0X03 && data[3] == 0X61 && data[4] == 0X03 && data[5] == 0X02 && data[6] == 0X66)
  173. {
  174. pmu_set_ack(_MSGID_SET,MSGID_SET_RADAR_FB,0x12,0);
  175. }
  176. else if(data[2] == 0X03 && data[3] == 0X61 && data[4] == 0X00 && data[5] == 0X03 && data[6] == 0X64)
  177. {
  178. pmu_set_ack(_MSGID_SET,MSGID_SET_RADAR_FB,0x100,0);
  179. }
  180. else
  181. {
  182. frame_num = 0;
  183. memcpy(&mimo_version[frame_num],&data[4],4);
  184. frame_num += 4;
  185. frame_head = true;
  186. }
  187. }
  188. //断料记
  189. else if(data[0] == 0xFB && data[1] == 0x03 && data[2] == 0)
  190. {
  191. //设置距离最大值反馈
  192. if(data[3] == 0xB2 && data[4] == 0xE1)
  193. {
  194. pmu_set_ack(_MSGID_SET,MSGID_SET_LACKLOSS_CAL,mimo_lackloss.cal_distance,mimo_lackloss.strength);
  195. }
  196. }
  197. //流量计
  198. else if(data[0] == 0xFB && data[1] == 0x10) //雷达版本和流量计协议有冲突
  199. {
  200. switch (data[2])
  201. {
  202. case 0:
  203. if(data[4] == 0XD1) //流速K
  204. {
  205. flow_mimo1.flow_k = data[5] * 256 + data[6];
  206. }
  207. else if(data[4] == 0XC1)//设置流速K ack
  208. {
  209. if(data[6] == 0)
  210. {
  211. flow_mimo1.flow_k = flow_mimo1.flow_calk;
  212. if(Dev.Flow_Link1.connect_status == COMP_NORMAL && Dev.Flow_Link2.connect_status != COMP_NORMAL)
  213. {
  214. pmu_set_ack(_MSGID_SET,MSGID_SET_MIMO_FLOW,flow_mimo1.flow_k,0);
  215. }
  216. }
  217. }
  218. else if(data[4] == 0xE2)
  219. {
  220. if(data[6] == 0 && Dev.Flow_Link1.connect_status == COMP_NORMAL && Dev.Flow_Link2.connect_status != COMP_NORMAL)
  221. {
  222. pmu_set_ack(_MSGID_SET,MSGID_SET_FLOW_BACKGROUND,0,0);
  223. }
  224. flow_inf.ch1.clear_background = false;
  225. }
  226. else if (data[4] == 0XEB)//sn 两包 协议冲突 协议有问题
  227. {
  228. for( i= 0;i<2;i++) //内容第一自字节0X0F?先舍弃一字节,
  229. {
  230. flow_mimo1.sn[2*i] = ((data[6 + i] >> 4) & 0xf) + '0';
  231. flow_mimo1.sn[2*i+1] = (data[6 + i] & 0xf )+ '0';
  232. }
  233. frame_num = 21;//流量序列号的标记
  234. }
  235. else if(data[4] == 0XEC)//软件号
  236. {
  237. flow_mimo1.soft_version[0] = data[5] + '0';
  238. flow_mimo1.soft_version[1] = data[6] + '0';
  239. }
  240. break;
  241. case 1:
  242. if(data[4] == 0XD1)
  243. {
  244. flow_mimo2.flow_k = data[5] * 256 + data[6];
  245. }
  246. else if(data[4] == 0XC1)
  247. {
  248. if(data[6] == 0)
  249. {
  250. flow_mimo2.flow_k = flow_mimo2.flow_calk;
  251. if(Dev.Flow_Link1.connect_status == COMP_NORMAL && Dev.Flow_Link2.connect_status == COMP_NORMAL)
  252. {
  253. pmu_set_ack(_MSGID_SET,MSGID_SET_MIMO_FLOW,flow_mimo1.flow_k,flow_mimo2.flow_k);
  254. }
  255. else if(Dev.Flow_Link1.connect_status != COMP_NORMAL && Dev.Flow_Link2.connect_status == COMP_NORMAL)
  256. {
  257. pmu_set_ack(_MSGID_SET,MSGID_SET_MIMO_FLOW,0,flow_mimo2.flow_k);
  258. }
  259. }
  260. }
  261. else if(data[4] == 0xE2)
  262. {
  263. if(data[6] == 0 && Dev.Flow_Link1.connect_status == COMP_NORMAL && Dev.Flow_Link2.connect_status == COMP_NORMAL)
  264. {
  265. pmu_set_ack(_MSGID_SET,MSGID_SET_FLOW_BACKGROUND,0,0);
  266. }
  267. flow_inf.ch1.clear_background = false;
  268. }
  269. break;
  270. default:
  271. break;
  272. }
  273. }
  274. else
  275. {
  276. if(frame_num == 21)
  277. {
  278. for( i=0;i<5;i++)
  279. {
  280. flow_mimo1.sn[4+2*i] = ((data[i] >> 4) & 0xf) + '0';
  281. flow_mimo1.sn[4+2*i+1] = (data[i] & 0xf )+ '0';
  282. }
  283. //flow_mimo1.sn[1] = 'F';
  284. frame_num = 0;
  285. }
  286. if(frame_num <= 20)
  287. {
  288. if(frame_head == true)
  289. {
  290. memcpy(&mimo_version[frame_num],&data[0],8);
  291. frame_num += 8;
  292. }
  293. if(frame_num == 0x1c) //恩曌SN取中间日期12位,其他有问题
  294. {
  295. checksum = 0x01;
  296. for(uint8_t i = 0; i < 27; i++)
  297. {
  298. checksum += mimo_version[i];
  299. }
  300. if((checksum & 0xFF) == mimo_version[27])
  301. {
  302. memcpy(&soft_ver,&mimo_version[23],4);
  303. switch (mimo_version[18])
  304. {
  305. case 0x00:
  306. mimo_ter_info.version[0] = 'E';
  307. mimo_ter_info.version[1] = 'B';
  308. mimo_ter_info.version[2] = '0';
  309. mimo_ter_info.version[3] = '0';
  310. Int2String(soft_ver,&mimo_ter_info.version[4],6);
  311. memcpy(&mimo_ter_info.hard_version,&mimo_version[19],4);
  312. if(mimo_ter_info.hard_version == 210221)
  313. {
  314. mimo_ter_info.version[3] = 'J';
  315. }
  316. for( i= 0;i<9;i++)
  317. {
  318. mimo_ter_info.sn[2*i] = ((mimo_version[7 + i] >> 4) & 0xf) + '0';
  319. mimo_ter_info.sn[2*i+1] = (mimo_version[7 + i] & 0xf )+ '0';
  320. }
  321. //memcpy(&mimo_ter_info.sn[0],&mimo_version[4],18);
  322. regist_dev_info(&dev_ter,DEVICE_TERRA,false,mimo_ter_info.sn,18,mimo_ter_info.version,10,NULL,0,"mimo",5);
  323. mimo_ter_info.get_radar_ver_flag = true;
  324. mimo_ter_info.Link.boot_flag = false;
  325. break;
  326. case 0x03:
  327. mimo_f_info.version[0] = 'E';
  328. mimo_f_info.version[1] = '1';
  329. mimo_f_info.version[2] = '0';
  330. mimo_f_info.version[3] = '0';
  331. Int2String(soft_ver,&mimo_f_info.version[4],6);
  332. memcpy(&mimo_f_info.hard_version,&mimo_version[19],4);
  333. if(mimo_f_info.hard_version == 190302) //恩曌协议定义
  334. {
  335. mimo_f_info.version[2] = '1'; //极翼
  336. mimo_f_info.version[3] = 'J';
  337. }
  338. else
  339. {
  340. mimo_f_info.version[2] = '0'; //vk
  341. mimo_f_info.version[3] = 'V';
  342. }
  343. for( i= 0;i<9;i++)
  344. {
  345. mimo_f_info.sn[2*i] = ((mimo_version[7 + i] >> 4) & 0xf) + '0';
  346. mimo_f_info.sn[2*i+1] = (mimo_version[7 + i] & 0xf )+ '0';
  347. }
  348. //memcpy(&mimo_f_info.sn[0],&mimo_version[4],12);
  349. regist_dev_info(&dev_obsf,DEVICE_OBSF,false,mimo_f_info.sn,18,mimo_f_info.version,10,mimo_f_info.version,10,"mimo",5);
  350. mimo_f_info.get_radar_ver_flag = true;
  351. mimo_f_info.Link.boot_flag = false;
  352. break;
  353. case 0x04:
  354. mimo_b_info.version[0] = 'E';
  355. mimo_b_info.version[1] = '2';
  356. mimo_b_info.version[2] = '0';
  357. mimo_b_info.version[3] = '0';
  358. Int2String(soft_ver,&mimo_b_info.version[4],6);
  359. memcpy(&mimo_b_info.hard_version,&mimo_version[19],4);
  360. if(mimo_b_info.hard_version == 190302) //恩曌协议定义
  361. {
  362. mimo_b_info.version[2] = '1'; //极翼
  363. mimo_b_info.version[3] = 'J';
  364. }
  365. else
  366. {
  367. mimo_b_info.version[2] = '0'; //vk
  368. mimo_b_info.version[3] = 'V';
  369. }
  370. for( i= 0;i<9;i++)
  371. {
  372. mimo_b_info.sn[2*i] = ((mimo_version[7 + i] >> 4) & 0xf) + '0';
  373. mimo_b_info.sn[2*i+1] = (mimo_version[7 + i] & 0xf )+ '0';
  374. }
  375. //memcpy(&mimo_b_info.sn[0],&mimo_version[4],12);
  376. regist_dev_info(&dev_obsb,DEVICE_OBSB,false,mimo_b_info.sn,18,mimo_b_info.version,10,mimo_b_info.version,10,"mimo",5);
  377. mimo_b_info.get_radar_ver_flag = true;
  378. mimo_b_info.Link.boot_flag = false;
  379. break;
  380. default:
  381. break;
  382. }
  383. frame_num = 0;
  384. frame_head = false;
  385. pmu_send = PMU_SEND_VERSION;
  386. }
  387. }
  388. }
  389. else
  390. {
  391. }
  392. }
  393. // char_to_hex_string(&data[5], 3, &mimo_ter_info.version[4], 6, "00");
  394. // mimo_ter_info.soft_verison = ((data[5] & 0xff) << 16) + ((data[6] & 0xff) << 8) + (data[7] & 0xff);
  395. break;
  396. default:
  397. break;
  398. }
  399. }
  400. /**
  401. * @file can_recv_mocib_F_obstacle
  402. * @brief 莫之比前避障解析
  403. * @param none
  404. * @details
  405. * @author Zhang Sir
  406. **/
  407. bool obs_f_is_link = false;
  408. void can_recv_mocib_F_obstacle(uint8_t *data)
  409. {
  410. uavr11_info.distance_x= (data[0] << 8) + data[1] - 32768;
  411. uavr11_info.distance_y = (data[2] << 8) + data[3];
  412. // if(abs(uavr11_info.distance_x) > 400)
  413. // {
  414. // uavr11_info.distance_y = 0;
  415. // uavr11_info.distance_x = 0;
  416. // }
  417. uavr11_info.Link.connect_status = COMP_NORMAL;
  418. uavr11_info.Link.recv_time = HAL_GetTick();
  419. }
  420. // /**
  421. // * @brief 恩曌360雷达
  422. // */
  423. // #pragma pack(push)
  424. // #pragma pack(1)
  425. // typedef struct
  426. // {
  427. // uint8_t totalSect; //总分区数
  428. // uint8_t validSect; // 有效分区数
  429. // uint8_t cycleCounter;
  430. // uint8_t reserve0;
  431. // uint32_t reserve : 20;
  432. // uint32_t height : 12; // 精度 0.01m
  433. // } FrameHeader1S;
  434. // typedef struct
  435. // {
  436. // uint8_t sectID; //分区 ID
  437. // uint16_t dis; //距离
  438. // int16_t ele;
  439. // uint8_t rcs; //目标雷达截面积
  440. // int16_t reserve1;
  441. // } SectionPackS;
  442. // typedef struct
  443. // {
  444. // uint32_t ID;
  445. // uint8_t data[8];
  446. // } CanMessage_t;
  447. // #pragma pack(pop)
  448. // #define MAX_SECTNUM 180
  449. // typedef struct
  450. // {
  451. // uint32_t totalSect; //总分区个数,数组中对应位置对应目标所在分区
  452. // uint32_t validSect; //总分区个数,数组中对应位置对应目标所在分区
  453. // uint32_t completeQ; // 0 代表无数据 1 代表数据接收到但不全 2 代表全部接收成功
  454. // float height;
  455. // float dis[MAX_SECTNUM]; // 雷达到目标距离,当目标不存在时距离为
  456. // float ele[MAX_SECTNUM]; // 目标的 RCS
  457. // float rcs[MAX_SECTNUM]; // 目标的 RCS
  458. // } TargetInfoS; // 原始目标结构信息
  459. // TargetInfoS Targetbuffer = {0}; // 用于缓存
  460. // TargetInfoS TargetOut = {0};
  461. // static int LastSection = -1;
  462. // int ValidSect = 0;
  463. // comp_status mimo360_link_status = COMP_NOEXIST;
  464. // void can_recv_mocib_360_obstacle(uint32_t cellCanID, uint8_t data[], uint8_t len)
  465. // {
  466. // int index;
  467. // CanMessage_t *can_tmp_ptr = NULL;
  468. // CanMessage_t can_tmp;
  469. // FrameHeader1S *frameHead_ptr;
  470. // SectionPackS *pack_ptr;
  471. // can_tmp_ptr = &can_tmp;
  472. // can_tmp_ptr->ID = cellCanID;
  473. // memcpy(&can_tmp_ptr->data[0], data, len);
  474. // mimo360_link_status = COMP_NORMAL;
  475. // if (can_tmp_ptr->ID == 0x301) // 检测到帧头
  476. // {
  477. // if (Targetbuffer.completeQ == 1) // 如果数据未接完
  478. // {
  479. // memcpy(&TargetOut, &Targetbuffer, sizeof(Targetbuffer));
  480. // }
  481. // memset(&Targetbuffer, 0, sizeof(Targetbuffer));
  482. // frameHead_ptr = (FrameHeader1S *)can_tmp_ptr->data;
  483. // Targetbuffer.totalSect = frameHead_ptr->totalSect;
  484. // Targetbuffer.height = frameHead_ptr->height / 100.0F;
  485. // if (frameHead_ptr->validSect == 0) // 如果不存在分区数据
  486. // {
  487. // Targetbuffer.completeQ = 2;
  488. // Targetbuffer.validSect = 0;
  489. // memcpy(&TargetOut, &Targetbuffer, sizeof(Targetbuffer));
  490. // }
  491. // else // 如果存在分区数据
  492. // {
  493. // ValidSect = frameHead_ptr->validSect;
  494. // Targetbuffer.completeQ = 1;
  495. // }
  496. // LastSection = -1;
  497. // }
  498. // else if (can_tmp_ptr->ID == 0x302) // 检测到目标数据
  499. // {
  500. // pack_ptr = (SectionPackS *)can_tmp_ptr->data;
  501. // if (Targetbuffer.completeQ == 1) //如果数据未接收完
  502. // {
  503. // index = pack_ptr->sectID; //获取分区 ID
  504. // if (LastSection == -1)
  505. // {
  506. // Targetbuffer.dis[index] = pack_ptr->dis * 0.01F;
  507. // Targetbuffer.ele[index] = pack_ptr->ele * 0.01F;
  508. // Targetbuffer.rcs[index] = pack_ptr->rcs;
  509. // Targetbuffer.validSect++;
  510. // LastSection = index;
  511. // }
  512. // else if (LastSection < index) //分区数据是按照从小到大输出才是正确的
  513. // {
  514. // Targetbuffer.dis[index] = pack_ptr->dis * 0.01F;
  515. // Targetbuffer.ele[index] = pack_ptr->ele * 0.1F;
  516. // Targetbuffer.rcs[index] = pack_ptr->rcs;
  517. // Targetbuffer.validSect++;
  518. // }
  519. // else // 如果不是则存在丢失包含帧 ID 的多个数据包
  520. // {
  521. // Targetbuffer.completeQ = 0; //数据不保存
  522. // }
  523. // if (Targetbuffer.completeQ == 1)
  524. // {
  525. // if (ValidSect == Targetbuffer.validSect) //有效个数等于实际接收个数
  526. // {
  527. // Targetbuffer.completeQ = 2;
  528. // memcpy(&TargetOut, &Targetbuffer, sizeof(Targetbuffer));
  529. // memset(&Targetbuffer, 0, sizeof(Targetbuffer));
  530. // }
  531. // }
  532. // }
  533. // }
  534. // }
  535. /**
  536. * @file can_recv_mocib_B_obstacle
  537. * @brief 莫之比后避障障解析
  538. * @param none
  539. * @details
  540. * @author Zhang Sir
  541. **/
  542. bool obs_b_is_link = false;
  543. void can_recv_mocib_B_obstacle(uint8_t *data)
  544. {
  545. uavr12_info.distance_x = (data[0] << 8) + data[1] - 32768;
  546. uavr12_info.distance_y = (data[2] << 8) + data[3];
  547. // if(abs(uavr12_info.distance_x) > 400)
  548. // {
  549. // uavr12_info.distance_x = 0;
  550. // uavr12_info.distance_y = 0;
  551. // }
  552. uavr12_info.Link.connect_status = COMP_NORMAL;
  553. uavr12_info.Link.recv_time = HAL_GetTick();
  554. }
  555. /**
  556. * @file can_recv_mocib_L_obstacle
  557. * @brief 莫之比左避障障解析
  558. * @param none
  559. * @details
  560. * @author ZHOU
  561. **/
  562. void can_recv_mocib_L_obstacle(uint8_t *data)
  563. {
  564. uavr13_info.distance_x = (data[0] << 8) + data[1] - 32768;
  565. uavr13_info.distance_y = (data[2] << 8) + data[3];
  566. // if(abs(uavr12_info.distance_x) > 400)
  567. // {
  568. // uavr12_info.distance_x = 0;
  569. // uavr12_info.distance_y = 0;
  570. // }
  571. uavr13_info.Link.connect_status = COMP_NORMAL;
  572. uavr13_info.Link.recv_time = HAL_GetTick();
  573. }
  574. /**
  575. * @file can_recv_mocib_R_obstacle
  576. * @brief 莫之比右避障障解析
  577. * @param none
  578. * @details
  579. * @author ZHOU
  580. **/
  581. void can_recv_mocib_R_obstacle(uint8_t *data)
  582. {
  583. uavr14_info.distance_x = (data[0] << 8) + data[1] - 32768;
  584. uavr14_info.distance_y = (data[2] << 8) + data[3];
  585. // if(abs(uavr12_info.distance_x) > 400)
  586. // {
  587. // uavr12_info.distance_x = 0;
  588. // uavr12_info.distance_y = 0;
  589. // }
  590. uavr14_info.Link.connect_status = COMP_NORMAL;
  591. uavr14_info.Link.recv_time = HAL_GetTick();
  592. }
  593. uint32_t uavr20_ver_time = 0;
  594. uint32_t uavr20_sensi_time = 0;
  595. char can_get_uavr21_ver_comp = 0;
  596. /**
  597. * @file can_sendmsg_uavr20
  598. * @brief 给墨汁比雷达发送无人机姿态信息
  599. * @param none
  600. * @details
  601. * @author Zhang Sir
  602. **/
  603. uint32_t uavr20_send_time = 0;
  604. void can_sendmsg_uavr20(void)
  605. {
  606. if (uavr12_info.Link.connect_status == COMP_NORMAL || uavr11_info.Link.connect_status == COMP_NORMAL ||
  607. uavr56_info.Link.connect_status == COMP_NORMAL || uavr13_info.Link.connect_status == COMP_NORMAL ||
  608. uavr14_info.Link.connect_status == COMP_NORMAL)
  609. {
  610. //10hz发送
  611. if ((HAL_GetTick() - uavr20_send_time > 100) && planep.lock_status == 1)
  612. {
  613. uavr20_send_time = HAL_GetTick();
  614. int16_t index = 0;
  615. short tmpShort = 0;
  616. uint8_t send_uavr20_data[16] = {0};
  617. // 开头
  618. send_uavr20_data[index++] = 0XA5;
  619. // 俯仰
  620. tmpShort = planep.pitch_angle;
  621. short2buf(&send_uavr20_data[index], &tmpShort);
  622. index += 2;
  623. // 前后速度
  624. tmpShort = planep.E_vel * sinf(planep.yaw / 100.0f * DEG_TO_RAD) +
  625. planep.N_vel * cosf(planep.yaw / 100.0f * DEG_TO_RAD);
  626. short2buf(&send_uavr20_data[index], &tmpShort);
  627. index += 2;
  628. // 横滚
  629. tmpShort = planep.roll_angle;
  630. short2buf(&send_uavr20_data[index], &tmpShort);
  631. index += 2;
  632. // 左右速度
  633. tmpShort = planep.E_vel * cosf(planep.yaw / 100.0f * DEG_TO_RAD) +
  634. planep.N_vel * sinf(planep.yaw / 100.0f * DEG_TO_RAD);
  635. short2buf(&send_uavr20_data[index], &tmpShort);
  636. index += 2;
  637. // 后边的都没用上
  638. // 上下加速度
  639. tmpShort = planep.alt_vel;
  640. short2buf(&send_uavr20_data[index], &tmpShort);
  641. index += 2;
  642. // 仿地最近距离
  643. tmpShort = uavh30_dist.near;
  644. short2buf(&send_uavr20_data[index], &tmpShort);
  645. index += 2;
  646. // 仿地最远距离
  647. tmpShort = uavh30_dist.far;
  648. short2buf(&send_uavr20_data[index], &tmpShort);
  649. index += 2;
  650. // 结束
  651. send_uavr20_data[index++] = 0X5A;
  652. can_send_msg_normal(send_uavr20_data, sizeof(send_uavr20_data), SEND_UAV20_MSG);
  653. }
  654. //读取前雷达版本
  655. else
  656. {
  657. //读取前雷达灵敏度
  658. if (uavr11_info.Link.connect_status == COMP_NORMAL && uavr11_info.get_radar_sensi_flag == false &&
  659. uavr11_info.get_radar_sensi_count < 5)
  660. {
  661. if (HAL_GetTick() - uavr20_sensi_time > 1000)
  662. {
  663. // 开头
  664. uint8_t send_uavr20_sensi[1] = {0};
  665. send_uavr20_sensi[0] = 0x11;
  666. can_send_msg_normal(send_uavr20_sensi, 1, CAN_UAVRH_SENSI_RA);
  667. uavr20_sensi_time = HAL_GetTick();
  668. uavr11_info.get_radar_sensi_count++;
  669. }
  670. }
  671. else
  672. {
  673. //读取后雷达灵敏度
  674. if (uavr12_info.Link.connect_status == COMP_NORMAL && uavr12_info.get_radar_sensi_flag == false &&
  675. uavr12_info.get_radar_sensi_count < 5)
  676. {
  677. if (HAL_GetTick() - uavr20_sensi_time > 1000)
  678. {
  679. // 开头
  680. uint8_t send_uavr20_sensi[1] = {0};
  681. send_uavr20_sensi[0] = 0x12;
  682. can_send_msg_normal(send_uavr20_sensi, 1, CAN_UAVRH_SENSI_RA);
  683. uavr20_sensi_time = HAL_GetTick();
  684. uavr12_info.get_radar_sensi_count++;
  685. }
  686. }
  687. else if(uavr56_info.Link.connect_status == COMP_NORMAL && uavr56_info.get_radar_sensi_flag == false &&
  688. uavr56_info.get_radar_sensi_count < 5)
  689. {
  690. if (HAL_GetTick() - uavr20_sensi_time > 1000)
  691. {
  692. // 开头
  693. uint8_t send_uavr20_sensi[1] = {0};
  694. send_uavr20_sensi[0] = 0x0B;
  695. can_send_msg_normal(send_uavr20_sensi, 1, CAN_UAVRH_SENSI_RA);
  696. uavr20_sensi_time = HAL_GetTick();
  697. uavr56_info.get_radar_sensi_count++;
  698. }
  699. }
  700. }
  701. }
  702. }
  703. }
  704. bool uavrhup_getr1_ack = false;
  705. short obsfradar_sensitivity = 50;
  706. short obsbradar_sensitivity = 50;
  707. /**
  708. * @file can_set_radar_sensi
  709. * @brief 设置雷达灵敏度
  710. * @param none
  711. * @details
  712. * @author Zhang Sir
  713. **/
  714. void can_set_radar_sensi()
  715. {
  716. static int radar_sensi_ack_time = 0;
  717. // 设置前雷达灵敏度
  718. if (uavr11_info.get_radar_sensi_flag == true &&
  719. uavr11_info.fcu_set_sensi_flag == true && uavr11_info.set_radar_sensi_count < 5 &&
  720. HAL_GetTick() - uavr20_sensi_time > 1000 && uavr11_info.Link.connect_status == COMP_NORMAL)
  721. {
  722. uint8_t send_uavr20_sensi[3] = {0};
  723. uavr11_info.set_radar_sensi_count++;
  724. uavr20_sensi_time = HAL_GetTick();
  725. if (uavrhup_getr1_ack == false)
  726. {
  727. //设置灵敏度先进入boot模式 新版本不进入boot
  728. if(uavr11_info.soft_verison >= RADAR_NER_VERSION )
  729. {
  730. uavrhup_getr1_ack = true;
  731. }
  732. else
  733. {
  734. send_uavr20_sensi[0] = 0x11;
  735. can_send_msg_normal(send_uavr20_sensi, 1, CAN_UAVRH_UPDATE_S1);
  736. }
  737. uavr11_info.set_radar_sensi_ack = false;
  738. }
  739. else
  740. {
  741. if (uavr11_info.set_radar_sensi_ack == false)
  742. {
  743. send_uavr20_sensi[0] = 0x11;
  744. //大端方式发送
  745. send_uavr20_sensi[1] = (obsfradar_sensitivity >> 8) & 0xff;
  746. send_uavr20_sensi[2] = (obsfradar_sensitivity)&0xff;
  747. can_send_msg_normal(send_uavr20_sensi, sizeof(send_uavr20_sensi), CAN_UAVRH_SENSI_SA);
  748. }
  749. else
  750. {
  751. uavr11_info.fcu_set_sensi_flag = false;
  752. uavrhup_getr1_ack = false;
  753. uavr11_info.set_radar_sensi_ack = false;
  754. uavr11_info.set_radar_sensi_count = 0;
  755. }
  756. }
  757. //超过5次失败后恢复
  758. if (uavr11_info.set_radar_sensi_count >= 5)
  759. {
  760. uavr11_info.fcu_set_sensi_flag = false;
  761. uavrhup_getr1_ack = false;
  762. uavr11_info.set_radar_sensi_ack = false;
  763. uavr11_info.set_radar_sensi_count = 0;
  764. }
  765. }
  766. //设置后雷达灵敏度
  767. else if (uavr12_info.get_radar_sensi_flag == true &&
  768. uavr12_info.fcu_set_sensi_flag == true && uavr12_info.set_radar_sensi_count < 5 &&
  769. HAL_GetTick() - uavr20_sensi_time > 1000 && uavr12_info.Link.connect_status == COMP_NORMAL)
  770. {
  771. uint8_t send_uavr20_sensi[3] = {0};
  772. uavr12_info.set_radar_sensi_count++;
  773. uavr20_sensi_time = HAL_GetTick();
  774. if (uavrhup_getr1_ack == false)
  775. {
  776. //设置灵敏度先进入boot模式 新版本不进入boot
  777. if(uavr12_info.soft_verison >= RADAR_NER_VERSION )
  778. {
  779. uavrhup_getr1_ack = true;
  780. }
  781. else
  782. {
  783. //设置灵敏度先进入boot模式
  784. send_uavr20_sensi[0] = 0x12;
  785. can_send_msg_normal(send_uavr20_sensi, 1, CAN_UAVRH_UPDATE_S1);
  786. }
  787. uavr12_info.set_radar_sensi_ack = false;
  788. }
  789. else
  790. {
  791. if (uavr12_info.set_radar_sensi_ack == false)
  792. {
  793. send_uavr20_sensi[0] = 0x12;
  794. send_uavr20_sensi[1] = (obsbradar_sensitivity >> 8) & 0xff;
  795. send_uavr20_sensi[2] = (obsbradar_sensitivity)&0xff;
  796. can_send_msg_normal(send_uavr20_sensi, sizeof(send_uavr20_sensi), CAN_UAVRH_SENSI_SA);
  797. }
  798. else
  799. {
  800. uavr12_info.fcu_set_sensi_flag = false;
  801. uavrhup_getr1_ack = false;
  802. uavr12_info.set_radar_sensi_ack = false;
  803. uavr12_info.set_radar_sensi_count = 0;
  804. }
  805. }
  806. //超过5次失败后恢复
  807. if (uavr12_info.set_radar_sensi_count >= 5)
  808. {
  809. uavr12_info.fcu_set_sensi_flag = false;
  810. uavrhup_getr1_ack = false;
  811. uavr12_info.set_radar_sensi_ack = false;
  812. uavr12_info.set_radar_sensi_count = 0;
  813. }
  814. }
  815. //设置仿地雷达灵敏度
  816. else if (uavr56_info.get_radar_sensi_flag == true &&
  817. uavr56_info.fcu_set_sensi_flag == true && uavr56_info.set_radar_sensi_count < 5 &&
  818. HAL_GetTick() - uavr20_sensi_time > 1000 && uavr56_info.Link.connect_status == COMP_NORMAL)
  819. {
  820. uint8_t send_uavr20_sensi[3] = {0};
  821. uavr56_info.set_radar_sensi_count++;
  822. uavr20_sensi_time = HAL_GetTick();
  823. if (uavrhup_getr1_ack == false)
  824. {
  825. if(uavr56_info.soft_verison >= RADAR_NER_VERSION )
  826. {
  827. uavrhup_getr1_ack = true;
  828. }
  829. else
  830. {
  831. //设置灵敏度先进入boot模式
  832. send_uavr20_sensi[0] = 0x0B;
  833. can_send_msg_normal(send_uavr20_sensi, 1, CAN_UAVRH_UPDATE_S1);
  834. }
  835. uavr56_info.set_radar_sensi_ack = false;
  836. }
  837. else
  838. {
  839. if (uavr56_info.set_radar_sensi_ack == false)
  840. {
  841. send_uavr20_sensi[0] = 0x0B;
  842. send_uavr20_sensi[1] = (uavr56_info.fcu_set_sensi >> 8) & 0xff;
  843. send_uavr20_sensi[2] = (uavr56_info.fcu_set_sensi)&0xff;
  844. can_send_msg_normal(send_uavr20_sensi, sizeof(send_uavr20_sensi), CAN_UAVRH_SENSI_SA);
  845. }
  846. else
  847. {
  848. uavr56_info.fcu_set_sensi_flag = false;
  849. uavrhup_getr1_ack = false;
  850. uavr56_info.set_radar_sensi_ack = false;
  851. uavr56_info.set_radar_sensi_count = 0;
  852. }
  853. }
  854. //超过5次失败后恢复
  855. if (uavr56_info.set_radar_sensi_count >= 5)
  856. {
  857. uavr56_info.fcu_set_sensi_flag = false;
  858. uavrhup_getr1_ack = false;
  859. uavr56_info.set_radar_sensi_ack = false;
  860. uavr56_info.set_radar_sensi_count = 0;
  861. }
  862. }
  863. //设置莫之比避障灵敏度成功后ACK主控
  864. if (uavr11_info.set_radar_sensi_ack == true || uavr12_info.set_radar_sensi_ack == true || uavr56_info.set_radar_sensi_ack == true)
  865. {
  866. //同时设置有个1.5s间隔
  867. if(HAL_GetTick() - radar_sensi_ack_time > 1500)
  868. {
  869. radar_sensi_ack_time = HAL_GetTick();
  870. if (uavr11_info.set_radar_sensi_ack == true)
  871. {
  872. pmu_set_ack(22, 1, uavr11_info.get_radar_sensi,0);
  873. uavr11_info.set_radar_sensi_ack = false;
  874. uavr11_info.fcu_set_sensi_flag = false;
  875. }
  876. else if (uavr12_info.set_radar_sensi_ack == true)
  877. {
  878. pmu_set_ack(22, 2, uavr12_info.get_radar_sensi,0);
  879. uavr12_info.set_radar_sensi_ack = false;
  880. uavr12_info.fcu_set_sensi_flag = false;
  881. }
  882. else if(uavr56_info.set_radar_sensi_ack == true)
  883. {
  884. pmu_set_ack(22, 6, uavr56_info.get_radar_sensi,0);
  885. uavr56_info.set_radar_sensi_ack = false;
  886. uavr56_info.fcu_set_sensi_flag = false;
  887. }
  888. }
  889. }
  890. }
  891. void can_recv_mocib_updata_read_set_hookfunction(uint32_t cellCanID, uint8_t data[])
  892. {
  893. //AG代码 和雷达升级不兼容,优先升级
  894. if (Rupdate.update_flag == true)
  895. {
  896. //避障雷达升级
  897. if (Rupdate.buf_flag == false)
  898. {
  899. memcpy(Rupdate.update_buf, data, 8);
  900. Rupdate.buf_flag = true;
  901. switch (cellCanID)
  902. {
  903. case 0x7E1:
  904. Rupdate.U7E1 = true;
  905. break;
  906. case 0x7E3:
  907. Rupdate.U7E3 = true;
  908. break;
  909. case 0x7E6:
  910. Rupdate.U7E6 = true;
  911. break;
  912. default:
  913. break;
  914. }
  915. }
  916. }
  917. else
  918. {
  919. switch (cellCanID)
  920. {
  921. //莫之比雷达反馈版本信息
  922. case CAN_UAVRH_UPDATE_R1:
  923. uavrhup_getr1_ack = true;
  924. break;
  925. //case CAN_UAVRH_VER_R:
  926. // if (uavr11_info.get_radar_ver_flag == false && can_get_uavr21_ver_comp == 1)
  927. // {
  928. // //char_to_hex_string(data, 4, uavr11_info.version, 10, "11");
  929. // uavr11_info.get_radar_ver_flag = true;
  930. // //升完级发送版本信息
  931. // if(HAL_GetTick() > 10000)
  932. // {
  933. // pmu_send = VERSION;
  934. // }
  935. // }
  936. // else if (uavr12_info.get_radar_ver_flag == false && can_get_uavr21_ver_comp == 2)
  937. // {
  938. // //char_to_hex_string(data, 4, uavr12_info.version, 10, "12");
  939. // uavr12_info.get_radar_ver_flag = true;
  940. // if(HAL_GetTick() > 10000)
  941. // {
  942. // pmu_send = VERSION;
  943. // }
  944. // }
  945. // else if (uavr56_info.get_radar_ver_flag == false && can_get_uavr21_ver_comp == 3)
  946. // {
  947. // //char_to_hex_string(data, 4, uavr56_info.version, 10, "56");
  948. // uavr56_info.get_radar_ver_flag = true;
  949. // if(HAL_GetTick() > 10000)
  950. // {
  951. // pmu_send = VERSION;
  952. // }
  953. // }
  954. // break;
  955. //莫之比雷达设置灵敏度及反馈
  956. case CAN_UAVRH_SENSI_SA:
  957. if (data[0] == 0x11)
  958. {
  959. uavr11_info.set_radar_sensi_ack = true;
  960. //莫之比大端模式
  961. uavr11_info.get_radar_sensi = ((data[1] << 8) & 0xff00) + data[2];
  962. }
  963. else if (data[0] == 0x12)
  964. {
  965. uavr12_info.set_radar_sensi_ack = true;
  966. //莫之比大端模式
  967. uavr12_info.get_radar_sensi = ((data[1] << 8) & 0xff00) + data[2];
  968. }
  969. else if(data[0] == 0x0B)
  970. {
  971. uavr56_info.set_radar_sensi_ack = true;
  972. uavr56_info.get_radar_sensi = ((data[1] << 8) & 0xff00) + data[2];
  973. }
  974. break;
  975. //莫之比雷达读取灵敏度及反馈
  976. case CAN_UAVRH_SENSI_RA:
  977. if (data[0] == 0x11)
  978. {
  979. uavr11_info.get_radar_sensi_flag = true;
  980. //莫之比大端模式
  981. uavr11_info.get_radar_sensi = ((data[1] << 8) & 0xff00) + data[2];
  982. }
  983. else if (data[0] == 0x12)
  984. {
  985. uavr12_info.get_radar_sensi_flag = true; //莫之比大端模式
  986. uavr12_info.get_radar_sensi = ((data[1] << 8) & 0xff00) + data[2];
  987. }
  988. else if(data[0] == 0x0B)
  989. {
  990. uavr56_info.get_radar_sensi_flag = true;
  991. uavr56_info.get_radar_sensi = ((data[1] << 8) & 0xff00) + data[2];
  992. }
  993. default:
  994. break;
  995. }
  996. }
  997. }
  998. /**
  999. * @file can_send_info_to_mimo
  1000. * @brief 给恩曌避障发送姿态信息
  1001. * @param none
  1002. * @details
  1003. * @author Zhang Sir
  1004. **/
  1005. void can_send_info_to_mimo()
  1006. {
  1007. static int mimo_50HZ = 0;
  1008. static int mimo_49HZ = 0;
  1009. if (mimo_f_info.Link.connect_status == COMP_NORMAL || mimo_b_info.Link.connect_status == COMP_NORMAL /*||
  1010. mimo_360_info.connect_status == COMP_NORMAL*/ || (Dev.Part_Fradar_Link.connect_status == COMP_NORMAL && Dev.Part_radarF.facid == FAC_MIMO_RF) ||
  1011. (uavr12_info.Link.connect_status == COMP_NORMAL || uavr11_info.Link.connect_status == COMP_NORMAL))
  1012. {
  1013. int16_t index = 0;
  1014. short tmpShort = 0;
  1015. int8_t tmpChar = 0;
  1016. uint8_t send_mimo_data[8] = {0};
  1017. if (HAL_GetTick() - mimo_50HZ > 20)
  1018. {
  1019. mimo_50HZ = HAL_GetTick();
  1020. // tmpShort = 1;
  1021. // short2buf(&send_mimo_data[index], &tmpShort);
  1022. // index += 2;
  1023. // // 俯仰
  1024. // tmpShort = planep.pitch_angle;
  1025. // short2buf(&send_mimo_data[index], &tmpShort);
  1026. // index += 2;
  1027. // // 横滚
  1028. // tmpShort = planep.roll_angle;
  1029. // short2buf(&send_mimo_data[index], &tmpShort);
  1030. // index += 2;
  1031. // //航向
  1032. // if(planep.yaw < 0)
  1033. // tmpShort = planep.yaw + 360;
  1034. // else
  1035. // tmpShort = planep.yaw;
  1036. // short2buf(&send_mimo_data[index], &tmpShort);
  1037. // index += 2;
  1038. // can_send_msg_normal(send_mimo_data, sizeof(send_mimo_data), 0x3740403);
  1039. index = 0;
  1040. // 俯仰
  1041. tmpShort = -planep.roll_angle;
  1042. short2buf(&send_mimo_data[index], &tmpShort);
  1043. index += 2;
  1044. // 横滚
  1045. tmpShort = planep.pitch_angle;
  1046. short2buf(&send_mimo_data[index], &tmpShort);
  1047. index += 2;
  1048. //航向
  1049. if(planep.yaw < 0)
  1050. tmpShort = planep.yaw + 360;
  1051. else
  1052. tmpShort = planep.yaw;
  1053. short2buf(&send_mimo_data[index], &tmpShort);
  1054. index += 2;
  1055. // 前后速度
  1056. tmpChar = (planep.E_vel * sinf(planep.yaw / 100.0f * DEG_TO_RAD) +
  1057. planep.N_vel * cosf(planep.yaw / 100.0f * DEG_TO_RAD)) /
  1058. 10; //0.1m/s
  1059. send_mimo_data[index++] = tmpChar;
  1060. //雷达安装俯仰角
  1061. tmpChar = 0;
  1062. send_mimo_data[index] = tmpChar;
  1063. can_send_msg_normal(send_mimo_data, sizeof(send_mimo_data), CAN_MIMO_ATTI_INFO1);
  1064. }
  1065. if (HAL_GetTick() - mimo_49HZ > 21)
  1066. {
  1067. mimo_49HZ = HAL_GetTick();
  1068. index = 0;
  1069. //高度
  1070. tmpShort = planep.alt;
  1071. short2buf(&send_mimo_data[index], &tmpShort);
  1072. index += 2;
  1073. //俯仰角速度
  1074. tmpShort = 0;
  1075. short2buf(&send_mimo_data[index], &tmpShort);
  1076. index += 2;
  1077. //横滚角速度
  1078. tmpShort = 0;
  1079. short2buf(&send_mimo_data[index], &tmpShort);
  1080. index += 2;
  1081. // 左右速度
  1082. tmpChar = (planep.E_vel * cosf(planep.yaw / 100.0f * DEG_TO_RAD) +
  1083. planep.N_vel * sinf(planep.yaw / 100.0f * DEG_TO_RAD)) /
  1084. 10;
  1085. send_mimo_data[index++] = tmpChar;
  1086. //Z速度
  1087. tmpChar = planep.alt_vel / 10; //0.1m/s
  1088. send_mimo_data[index] = tmpChar;
  1089. can_send_msg_normal(send_mimo_data, sizeof(send_mimo_data), CAN_MIMO_ATTI_INFO2);
  1090. }
  1091. }
  1092. }
  1093. /**
  1094. * @file lidar_function
  1095. * @brief 雷达相关函数
  1096. * @param none
  1097. * @details
  1098. * @author Zhang Sir
  1099. **/
  1100. void send_mocib_radar_sensi(void)
  1101. {
  1102. static int radar_sensi_send_time = 0;
  1103. //uint8_t radar_can_buf[8] = {0};
  1104. if(HAL_GetTick() > 7000 && HAL_GetTick() - radar_sensi_send_time > 300)
  1105. {
  1106. //给FMU发送雷达灵敏度
  1107. radar_sensi_send_time = HAL_GetTick();
  1108. //上电后 检测到有雷达连接,向飞控发送雷达灵敏度信息
  1109. if (uavr11_info.Link.connect_status == COMP_NORMAL && uavr11_info.get_radar_sensi_flag == true &&
  1110. uavr11_info.send_fcu_sensi_count <= 3)
  1111. {
  1112. pmu_set_ack(22, 1, uavr11_info.get_radar_sensi,0);
  1113. uavr11_info.send_fcu_sensi_count++;
  1114. }
  1115. else if (uavr12_info.Link.connect_status == COMP_NORMAL && uavr12_info.get_radar_sensi_flag == true &&
  1116. uavr12_info.send_fcu_sensi_count <= 3)
  1117. {
  1118. pmu_set_ack(22, 2, uavr12_info.get_radar_sensi,0);
  1119. uavr12_info.send_fcu_sensi_count++;
  1120. }
  1121. else if (uavr56_info.Link.connect_status == COMP_NORMAL && uavr56_info.get_radar_sensi_flag == true &&
  1122. uavr56_info.send_fcu_sensi_count <= 3)
  1123. {
  1124. pmu_set_ack(22, 6, uavr56_info.get_radar_sensi,0);
  1125. uavr56_info.send_fcu_sensi_count++;
  1126. }
  1127. }
  1128. }
  1129. void lidar_function(void)
  1130. {
  1131. //莫之比避障雷达升级
  1132. if (radar_update_flag == true && uavr11_info.fcu_set_sensi_flag != true && uavr12_info.fcu_set_sensi_flag != true
  1133. && uavr56_info.fcu_set_sensi_flag != true)
  1134. {
  1135. Rupdate.update_flag = true;
  1136. Can_obstacle_update();
  1137. }
  1138. //上电给fcu发送雷达灵敏度
  1139. send_mocib_radar_sensi();
  1140. //设置莫之比避障雷达灵敏度
  1141. can_set_radar_sensi();
  1142. //获取电目雷达盲区、能量、原始数据开关
  1143. get_radar_blindAndPower_function();
  1144. //雷达升级不再给雷达发送信息,莫之比雷达发送姿态信息
  1145. if (radar_update_flag == false)
  1146. {
  1147. can_sendmsg_uavr20();
  1148. }
  1149. //给恩曌雷达发送姿态信息数据
  1150. can_send_info_to_mimo();
  1151. }
  1152. void can_recv_mocib_version_info(uint32_t cellCanID, uint8_t data[], uint8_t len)
  1153. {
  1154. static uint8_t frame_fi = 0,frame_bi = 0,frame_ti = 0;
  1155. switch (cellCanID)
  1156. {
  1157. //SN号
  1158. case CAN_OBSTARCLE11_SN:
  1159. if(frame_fi == 0)
  1160. {
  1161. memcpy(&uavr11_info.sn[0],&data[2],6);//要后六个字节
  1162. frame_fi += 6;
  1163. }
  1164. else if(frame_fi == 6)
  1165. {
  1166. memcpy(&uavr11_info.sn[frame_fi],&data[1],7);//要后7个字节
  1167. frame_fi += 7;
  1168. }
  1169. else if(frame_fi >= 13)
  1170. {
  1171. memcpy(&uavr11_info.sn[frame_fi],&data[1],3);
  1172. frame_fi = 0;
  1173. regist_dev_info(&dev_obsf,DEVICE_OBSF,false,uavr11_info.sn,20,NULL,0,NULL,0,"mocib",6);
  1174. uavr11_info.get_radar_sn_flag = true;
  1175. }
  1176. break;
  1177. case CAN_OBSTARCLE12_SN:
  1178. if(frame_bi == 0)
  1179. {
  1180. memcpy(&uavr12_info.sn[0],&data[2],6);//要后六个字节
  1181. frame_bi += 6;
  1182. }
  1183. else if(frame_bi == 6)
  1184. {
  1185. memcpy(&uavr12_info.sn[frame_bi],&data[1],7);//要后7个字节
  1186. frame_bi += 7;
  1187. }
  1188. else if(frame_bi >= 13)
  1189. {
  1190. memcpy(&uavr12_info.sn[frame_bi],&data[1],3);
  1191. frame_bi = 0;
  1192. regist_dev_info(&dev_obsb,DEVICE_OBSB,false,uavr12_info.sn,20,NULL,0,NULL,0,"mocib",6);
  1193. uavr12_info.get_radar_sn_flag = true;
  1194. }
  1195. break;
  1196. case CAN_OBSTARCLE56_SN:
  1197. if(frame_ti == 0)
  1198. {
  1199. memcpy(&uavr56_info.sn[0],&data[2],6);//要后六个字节
  1200. frame_ti += 6;
  1201. }
  1202. else if(frame_ti == 6)
  1203. {
  1204. memcpy(&uavr56_info.sn[frame_ti],&data[1],7);//要后7个字节
  1205. frame_ti += 7;
  1206. }
  1207. else if(frame_ti >= 13)
  1208. {
  1209. memcpy(&uavr56_info.sn[frame_ti],&data[1],3);
  1210. frame_ti = 0;
  1211. regist_dev_info(&dev_ter,DEVICE_TERRA,false,uavr56_info.sn,20,NULL,0,NULL,0,"mocib",6);
  1212. uavr56_info.get_radar_sn_flag = true;
  1213. }
  1214. break;
  1215. //版本信息
  1216. case 0x00eeff11:
  1217. uavr11_info.version[0] = 'M';
  1218. uavr11_info.version[1] = '1';
  1219. uavr11_info.version[2] = (data[1] + data[2]) + '0';
  1220. uavr11_info.version[3] = (data[3] + data[4]) + '0';
  1221. char_to_hex_string(&data[5], 3, &uavr11_info.version[4], 6, "00");
  1222. uavr11_info.soft_verison = ((data[5] & 0xff) << 16) + ((data[6] & 0xff) << 8) + (data[7] & 0xff);
  1223. uavr11_info.get_radar_ver_flag = true;
  1224. regist_dev_info(&dev_obsf,DEVICE_OBSF,false,NULL,0,uavr11_info.version,10,NULL,0,"mocib",6);
  1225. break;
  1226. case 0x00eeff12:
  1227. uavr12_info.version[0] = 'M';
  1228. uavr12_info.version[1] = '2';
  1229. uavr12_info.version[2] = (data[1] + data[2]) + '0';
  1230. uavr12_info.version[3] = (data[3] + data[4]) + '0';
  1231. char_to_hex_string(&data[5], 3, &uavr12_info.version[4], 6, "00");
  1232. uavr12_info.soft_verison = ((data[5] & 0xff) << 16) + ((data[6] & 0xff) << 8) + (data[7] & 0xff);
  1233. uavr12_info.get_radar_ver_flag = true;
  1234. regist_dev_info(&dev_obsb,DEVICE_OBSB,false,NULL,0,uavr12_info.version,10,NULL,0,"mocib",6);
  1235. break;
  1236. case 0x00eeff0b:
  1237. uavr56_info.version[0] = 'M';
  1238. uavr56_info.version[1] = 'B';
  1239. uavr56_info.version[2] = (data[1] + data[2]) + '0';
  1240. uavr56_info.version[3] = (data[3] + data[4]) + '0';
  1241. char_to_hex_string(&data[5], 3, &uavr56_info.version[4], 6, "00");
  1242. uavr56_info.soft_verison = ((data[5] & 0xff) << 16) + ((data[6] & 0xff) << 8) + (data[7] & 0xff);
  1243. uavr56_info.get_radar_ver_flag = true;
  1244. regist_dev_info(&dev_ter,DEVICE_TERRA,false,NULL,0,uavr56_info.version,10,NULL,0,"mocib",6);
  1245. break;
  1246. default:
  1247. break;
  1248. }
  1249. // if(HAL_GetTick() > 10000)
  1250. // {
  1251. pmu_send = PMU_SEND_VERSION;
  1252. // }
  1253. }
  1254. bool check_radar_update(void)
  1255. {
  1256. if (uavr12_info.Link.connect_status == COMP_NORMAL && uavr12_info.get_radar_sensi_flag == false &&
  1257. uavr12_info.get_radar_sensi_count < 5)
  1258. {
  1259. return false;
  1260. }
  1261. if (uavr11_info.Link.connect_status == COMP_NORMAL && uavr11_info.get_radar_sensi_flag == false &&
  1262. uavr11_info.get_radar_sensi_count < 5)
  1263. {
  1264. return false;
  1265. }
  1266. if (uavr56_info.Link.connect_status == COMP_NORMAL && uavr56_info.get_radar_sensi_flag == false &&
  1267. uavr56_info.get_radar_sensi_count < 5)
  1268. {
  1269. return false;
  1270. }
  1271. if(uavr11_info.fcu_set_sensi_flag == true ||uavr12_info.fcu_set_sensi_flag == true
  1272. || uavr56_info.fcu_set_sensi_flag == true)
  1273. {
  1274. return false;
  1275. }
  1276. return true;
  1277. }
  1278. void get_radar_blindAndPower_function( void )
  1279. {
  1280. uint8_t can_buf[8] = {0};
  1281. uint32_t can_id = 0;
  1282. static uint32_t time_1hz = 0;
  1283. if(!Check_Timer_Ready(&time_1hz,_1_HZ_))
  1284. return;
  1285. if (DM_f_info.Link.connect_status == COMP_NORMAL && DM_f_info.get_radar_blind_flag == false)
  1286. {
  1287. can_id = 0xA81300;
  1288. put_date_to_can(can_buf, 0x8, 0, 0, 0, 0, 0, 0, 0X7);
  1289. can_send_msg_normal(&can_buf[0], 8, can_id);
  1290. }
  1291. else if ((Dev.Part_Fradar_Link.connect_status == COMP_NORMAL && Dev.Part_radarF.facid == FAC_DM_RF_4D) &&
  1292. (DM_4DRADARMAG.get_DM4DF_Blind_spot_distance == false && DM4Dmsg_send_fmu == false))
  1293. {
  1294. can_id = 0xA81300;
  1295. put_date_to_can(can_buf, 0x8, 0, 0, 0, 0, 0, 0, 0X7);
  1296. can_send_msg_normal(&can_buf[0], 8, can_id);
  1297. }
  1298. else if(DM_f_info.Link.connect_status == COMP_NORMAL && DM_f_info.get_radar_power_flag == false)
  1299. {
  1300. can_id = 0xA81300;
  1301. put_date_to_can(can_buf,0x9,0,0,0,0,0,0,0X7);
  1302. can_send_msg_normal(&can_buf[0], 8, can_id);
  1303. }
  1304. else if(DM_f_info.Link.connect_status == COMP_NORMAL && DM_f_info.get_radar_rawSwitch_flag == false )
  1305. {
  1306. can_id = 0xA81300;
  1307. put_date_to_can(can_buf,0xB,0,0,0,0,0,0,0X7);
  1308. can_send_msg_normal(&can_buf[0], 8, can_id);
  1309. }
  1310. else if((Dev.Part_Fradar_Link.connect_status == COMP_NORMAL && Dev.Part_radarF.facid == FAC_DM_RF_4D) &&
  1311. (DM_4DRADARMAG.get_dotcloud_switch_4DF == false && DM4Dmsg_send_fmu == false))
  1312. {
  1313. can_id = 0xA81300;
  1314. put_date_to_can(can_buf,0xB,0,0,0,0,0,0,0X7);
  1315. can_send_msg_normal(&can_buf[0], 8, can_id);
  1316. }
  1317. if(DM_ter_info.Link.connect_status == COMP_NORMAL && DM_ter_info.get_radar_blind_flag == false)
  1318. {
  1319. can_id = 0x981300;
  1320. put_date_to_can(can_buf,0x8,0,0,0,0,0,0,0X7);
  1321. can_send_msg_normal(&can_buf[0], 8, can_id);
  1322. }
  1323. else if(DM_ter_info.Link.connect_status == COMP_NORMAL && DM_ter_info.get_radar_power_flag == false)
  1324. {
  1325. can_id = 0x981300;
  1326. put_date_to_can(can_buf,0x9,0,0,0,0,0,0,0X7);
  1327. can_send_msg_normal(&can_buf[0], 8, can_id);
  1328. }
  1329. else if(DM_ter_info.Link.connect_status == COMP_NORMAL && DM_ter_info.get_radar_rawSwitch_flag == false)
  1330. {
  1331. can_id = 0x981300;
  1332. put_date_to_can(can_buf,0xB,0,0,0,0,0,0,0X7);
  1333. can_send_msg_normal(&can_buf[0], 8, can_id);
  1334. }
  1335. else if((Dev.Part_Bradar_Link.connect_status == COMP_NORMAL && Dev.Part_radarB.facid == FAC_DM_RB_4D) &&
  1336. (DM_4DRADARMAG.get_dotcloud_switch_4DB == false && DM4Dmsg_send_fmu == false))
  1337. {
  1338. can_id = 0xB81300;
  1339. put_date_to_can(can_buf,0xB,0,0,0,0,0,0,0X7);
  1340. can_send_msg_normal(&can_buf[0], 8, can_id);
  1341. }
  1342. if ((Dev.Part_Fradar_Link.connect_status == COMP_NORMAL && Dev.Part_radarF.facid == FAC_DM_RF_4D) &&
  1343. (DM_4DRADARMAG.get_angel_4DF == false && DM4Dmsg_send_fmu == false))
  1344. {
  1345. can_id = 0xA81300;
  1346. put_date_to_can(can_buf, 0xD, 0, 0, 0, 0, 0, 0, 0X7);
  1347. can_send_msg_normal(&can_buf[0], 8, can_id);
  1348. }
  1349. else if ((Dev.Part_Fradar_Link.connect_status == COMP_NORMAL && Dev.Part_radarF.facid == FAC_DM_RF_4D) &&
  1350. (DM_4DRADARMAG.get_ground_filter_4DF == false && DM4Dmsg_send_fmu == false))
  1351. {
  1352. can_id = 0xA81300;
  1353. put_date_to_can(can_buf, 0xF, 0, 0, 0, 0, 0, 0, 0X7);
  1354. can_send_msg_normal(&can_buf[0], 8, can_id);
  1355. }
  1356. if ((Dev.Part_Bradar_Link.connect_status == COMP_NORMAL && Dev.Part_radarB.facid == FAC_DM_RB_4D) &&
  1357. (DM_4DRADARMAG.get_angel_4DB == false && DM4Dmsg_send_fmu == false))
  1358. {
  1359. can_id = 0xB81300;
  1360. put_date_to_can(can_buf, 0xD, 0, 0, 0, 0, 0, 0, 0X7);
  1361. can_send_msg_normal(&can_buf[0], 8, can_id);
  1362. }
  1363. else if ((Dev.Part_Bradar_Link.connect_status == COMP_NORMAL && Dev.Part_radarB.facid == FAC_DM_RB_4D) &&
  1364. (DM_4DRADARMAG.get_ground_filter_4DB == false && DM4Dmsg_send_fmu == false))
  1365. {
  1366. can_id = 0xB81300;
  1367. put_date_to_can(can_buf, 0xF, 0, 0, 0, 0, 0, 0, 0X7);
  1368. can_send_msg_normal(&can_buf[0], 8, can_id);
  1369. }
  1370. else if ((Dev.Part_Bradar_Link.connect_status == COMP_NORMAL && Dev.Part_radarB.facid == FAC_DM_RB_4D) &&
  1371. (DM_4DRADARMAG.get_DM4DB_Blind_spot_distance == false && DM4Dmsg_send_fmu == false))
  1372. {
  1373. can_id = 0xB81300;
  1374. put_date_to_can(can_buf, 0x8, 0, 0, 0, 0, 0, 0, 0X7);
  1375. can_send_msg_normal(&can_buf[0], 8, can_id);
  1376. }
  1377. }
  1378. // mimo_360info mimo360_info[MIMO_360_TotalSect];
  1379. // mimo_360status mimo360_status;
  1380. // Connect_check mimo_360_info;
  1381. // void mimo360_sort(mimo_360info *arr,uint16_t length)
  1382. // {
  1383. // if ( length < 2 )
  1384. // {
  1385. // return;
  1386. // }
  1387. // uint16_t num = 0, num1 = 0;
  1388. // mimo_360info tmp;
  1389. // for ( num = length - 1; num >= 1; num-- )
  1390. // {
  1391. // for ( num1 = 0; num1 <= num - 1; num1++ )
  1392. // {
  1393. // if ( ( ( arr + num1 )->dis0 ) > ( ( arr + num1 + 1 )->dis0 ) )
  1394. // {
  1395. // tmp = *( arr + num1 );
  1396. // *( arr + num1 ) = *( arr + num1 + 1 );
  1397. // *( arr + num1 + 1 ) = tmp;
  1398. // }
  1399. // }
  1400. // }
  1401. // }
  1402. // uint16_t test_index = 0;
  1403. // uint16_t compelte = 0;
  1404. // uint8_t radar360_proflag = 0;
  1405. // mimo_360_cont fmu_360info;
  1406. // void can_recv_mocib_new360_obstacle(uint32_t cellCanID, uint8_t data[], uint8_t len)
  1407. // {
  1408. // mimo_360_info.connect_status = COMP_NORMAL;
  1409. // mimo_360_info.recv_time = HAL_GetTick();
  1410. // switch (cellCanID)
  1411. // {
  1412. // case CAN_360MIMO_1ID:
  1413. // memcpy(&mimo360_status,&data[0],8);
  1414. // mimo360_status.index = 0;
  1415. // if(mimo360_status.nTarget == 0)
  1416. // {
  1417. // fmu_360info.total_tar = 0;
  1418. // memset(&fmu_360info.data[0],0,sizeof(mimo_360_data));
  1419. // }
  1420. // break;
  1421. // case CAN_360MIMO_2ID:
  1422. // if(mimo360_status.nTarget <= MIMO_360_TotalSect && mimo360_status.nTarget > 0)
  1423. // {
  1424. // for(uint8_t i = 0;i < 2;i++)
  1425. // {
  1426. // if(i == 0)
  1427. // {
  1428. // memcpy(&mimo360_info[mimo360_status.index].sectId0,&data[0],sizeof(mimo_360info));
  1429. // }
  1430. // else
  1431. // {
  1432. // memcpy(&mimo360_info[mimo360_status.index].sectId0,&data[4],sizeof(mimo_360info));
  1433. // }
  1434. // if(mimo360_status.nTarget - 1 == mimo360_status.index && radar360_proflag == 0)
  1435. // {
  1436. // //mimo360_sort(&mimo360_info[0],mimo360_status.nTarget);
  1437. // fmu_360info.TotalSect = mimo360_status.TotalSect;
  1438. // fmu_360info.total_tar = mimo360_status.nTarget;
  1439. // for(uint8_t j = 0;j < mimo360_status.nTarget;j++)
  1440. // {
  1441. // fmu_360info.data[j].sec_angle = mimo360_info[j].sectId0 * 360 / mimo360_status.TotalSect;
  1442. // fmu_360info.data[j].distance = mimo360_info[j].dis0 * mimo360_status.RangeRes/100; //cm
  1443. // fmu_360info.data[j].rcs0 = mimo360_info[j].rcs0;
  1444. // fmu_360info.data[j].el0 = mimo360_info[j].el0 * 0.5;
  1445. // }
  1446. // }
  1447. // mimo360_status.index++;
  1448. // }
  1449. // }
  1450. // break;
  1451. // default:
  1452. // break;
  1453. // }
  1454. // }