soft_obstacle.c 53 KB

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