soft_imu.c 29 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063
  1. #include "soft_imu.h"
  2. #include "hpm_math.h"
  3. #include "auto_pilot.h"
  4. #include "common.h"
  5. #include "control_attitude.h"
  6. #include "control_rate.h"
  7. #include "control_throttle.h"
  8. #include "dcm.h"
  9. #include "flight_mode.h"
  10. #include "hard_imu_uart3.h"
  11. #include "helpler_funtions.h"
  12. #include "lowpass_filter.h"
  13. #include "math.h"
  14. #include "my_crc.h"
  15. #include "my_math.h"
  16. #include "params.h"
  17. #include "quaternion.h"
  18. #include "soft_can_yy.h"
  19. #include "soft_delay.h"
  20. #include "soft_gs.h"
  21. #include "soft_motor_output.h"
  22. #include "soft_port_uart4.h"
  23. #include "soft_time.h"
  24. #include "ver_config.h"
  25. #include "mode_attitude.h"
  26. #include "bsp_V8M_YY_led.h"
  27. #include "vklink.h"
  28. #include <stdint.h>
  29. #include <string.h>
  30. /* 高度数据使用哪个的宏定义 */
  31. #define USE_BARO_ALT 0 // 气压高度
  32. #define USE_INTEG_ALT 1 // gps速度积分高度
  33. // 磁校准
  34. bool ci_jiao_zhun = false;
  35. // 通知 IMU 解锁
  36. bool notify_imu_unlock = false;
  37. // 通知 IMU 上锁
  38. bool notify_imu_lock = false;
  39. // 通知 IMU 禁用 GPS 高度
  40. bool notify_imu_disable_gpsalt = false;
  41. // 通知 IMU 启用 GPS 高度
  42. bool notify_imu_enable_gpsalt = false;
  43. /* 高度清零使用的记录偏移量 */
  44. static int clear_alt_offset = 0; // cm
  45. static int offset_alt = 0; // cm
  46. /* 导航数据结构体 */
  47. struct INS_DATA ins;
  48. /* imu 数据接收时间和互斥变量 */
  49. static volatile char ins_data_time_sem = 0;
  50. unsigned int ins_data_time = 0;
  51. /* imu 数据接收 */
  52. VKlink_Msg_Type imu_rx_msg;
  53. /* 地面站转发 imu 接收到的消息 */
  54. uint8_t need_gcs_tx_imu_rx_msg = 0;
  55. VKlink_Msg_Type gcs_tx_imu_msg = {0};
  56. // 原始IMU数据结构体
  57. REV_IMU raw_imu;
  58. // 原始GPS数据结构体
  59. REV_GPS raw_gps;
  60. // 原始传感器数据结构体
  61. REV_SENSOR raw_sensor;
  62. // 收到Imu数据标志位
  63. bool recieve_isimudata = false;
  64. // 收到Gps数据标志位
  65. bool recieve_isgpsdata = false;
  66. // 收到Sensor数据标志位
  67. bool recieve_issensordata = false;
  68. // DMA传输出错标志位
  69. bool dma_iserror = false;
  70. // imu 链接状态
  71. comp_status imu_link_status = COMP_NOEXIST;
  72. // 0---无校准 1-- 校准XY 2--校准XZ 3--校准完成 4--校准失败
  73. unsigned char mag_cal_status = MAG_CAL_NO;
  74. // 获得IMU版本号
  75. bool get_imu_version = false;
  76. // 获得 GPS 安装位置偏差
  77. bool get_gps_pos_param = false;
  78. // 获得 IMU 安装位置偏差
  79. bool get_imu_pos_param = true;
  80. struct imu_vklink_system
  81. {
  82. uint8_t head;
  83. uint8_t sysid;
  84. uint8_t compid;
  85. uint8_t tx_seq;
  86. uint8_t rx_seq;
  87. };
  88. static struct imu_vklink_system imu_vklink_sys = {
  89. .head = 0xfe, .sysid = 0, .tx_seq = 0, .rx_seq = 0, .compid = 0};
  90. /* 水平位置平均滤波 */
  91. static void horizental_pos_aver_filter(void);
  92. /* 时区转换 */
  93. void UTCToLocalTime(int timezone);
  94. /**
  95. * @brief imu 串口初始化
  96. *
  97. * @param imu_bps 串口波特率
  98. */
  99. void imu_uart3_initial(unsigned int imu_bps) { imu_uart3_init(imu_bps); }
  100. void imu_euler_angle_clear(void)
  101. {
  102. uint8_t calib_data[3] = {0};
  103. send_calibration_msg_to_imu(ATTITUE_CALIB, calib_data, 0);
  104. }
  105. /**
  106. * @brief gps 运动航向规范化
  107. */
  108. float get_normal_gpsyaw(float raw_yaw)
  109. {
  110. // 将航向角的范围归一化到-180--180之间
  111. if (raw_yaw > 180.0f)
  112. raw_yaw -= 360.0f;
  113. return raw_yaw;
  114. }
  115. #define BARO_NUM 5 // 要平均的气压高度的个数
  116. static int plane_baro_alt = 0;
  117. /**
  118. * @brief imu data 数据解析
  119. *
  120. */
  121. void dma_analysis_imudata(void)
  122. {
  123. // 上次接收解析时间
  124. static uint32_t last_recv_time = 0;
  125. uint32_t time_interval = micros() - last_recv_time;
  126. float dt = time_interval / 1000000.0f;
  127. if (dt < 0.0f || dt > 0.1f)
  128. dt = 0.005f;
  129. DCM_ByEuler(deg_to_rad(raw_imu._zitai_yaw * 0.01f),
  130. deg_to_rad(raw_imu._zitai_pitch * 0.01f),
  131. deg_to_rad(raw_imu._zitai_roll * 0.01f),
  132. ins.dcm);
  133. Quaternion_ByEuler(deg_to_rad(raw_imu._zitai_yaw * 0.01f),
  134. deg_to_rad(raw_imu._zitai_pitch * 0.01f),
  135. deg_to_rad(raw_imu._zitai_roll * 0.01f),
  136. ins.Q);
  137. pid_m_posx.vel_c = raw_imu._x_vel; // E向速度 cm/s
  138. pid_m_posy.vel_c = raw_imu._y_vel; // N向速度 cm/s
  139. pid_m_alt.vel_c = raw_imu._z_vel; // 垂直速度 IMU传递过来的是cm/s
  140. ins.horz_vel =
  141. get_norm(pid_m_posx.vel_c, pid_m_posy.vel_c); // 合成速度,单位cm/s
  142. pid_m_posx.acc_c = raw_imu._x_acc;
  143. pid_m_posy.acc_c = raw_imu._y_acc;
  144. horizental_pos_aver_filter();
  145. pid_m_alt.loc_c = (raw_imu._baro_alt);
  146. // _cxy.pc[0] = pid_m_posx.loc_c * 0.01f;
  147. // _cxy.pc[1] = pid_m_posy.loc_c * 0.01f;
  148. // _cxy.vc[0] = pid_m_posx.vel_c * 0.01f;
  149. // _cxy.vc[1] = pid_m_posy.vel_c * 0.01f;
  150. // _cxy.ac[0] = pid_m_posx.acc_c * 0.01f;
  151. // _cxy.ac[1] = pid_m_posy.acc_c * 0.01f;
  152. }
  153. void imu_attitude_ananlysis(void)
  154. {
  155. const struct yy_can_rx_msg_data *yy_can_rx_data = yy_can_rx_data_get();
  156. if ((yy_can_rx_data->imu_status & 0x01) == 0x01)
  157. {
  158. pid_m_yaw.angle_c = yy_can_rx_data->imu_yaw;
  159. }
  160. else
  161. {
  162. pid_m_yaw.angle_c = 360.0f - raw_imu._zitai_yaw / 100.0f;
  163. }
  164. pid_m_roll.angle_c = raw_imu._zitai_roll / 100.0f;
  165. pid_m_pitch.angle_c = raw_imu._zitai_pitch / 100.0f;
  166. pid_m_roll.gyro_c = raw_imu._y_gyro;
  167. pid_m_pitch.gyro_c = raw_imu._x_gyro;
  168. pid_m_yaw.gyro_c = apply(raw_imu._z_gyro, pid_m_yaw.gyro_c, 10.0f, 0.005f);
  169. pid_m_alt.acc_c = raw_imu._z_acc;
  170. // 垂直加速度
  171. // IMU传递过来的是cm/s/s..限制加速度试图解决加速度异常导致的飞机一直爬升。
  172. // 限制小了至少油门拉到底飞机可以下来。发现限制小了之后(+-100)会造成严重的超调震荡。猛加速猛减速。所以建议不能限制太小。
  173. pid_m_alt.acc_c = constrain_float(pid_m_alt.acc_c, -500.0f, +500.0f);
  174. }
  175. /**
  176. * @brief dma解析gps数据
  177. */
  178. void dma_analysis_gpsdata(void)
  179. {
  180. static int recieve_gps_time = 0;
  181. float recieve_gps_dt = 0.0f;
  182. recieve_gps_dt = (micros() - recieve_gps_time) / 1000000.0f;
  183. if (recieve_gps_dt < 0.0f)
  184. recieve_gps_dt = 0.05f;
  185. recieve_gps_time = micros();
  186. // 解析GPS航向角
  187. ins.gps_yaw = get_normal_gpsyaw(raw_gps._gps_yaw / 10.0f);
  188. ins.gps_alt = raw_gps._gps_alt_mm * 0.1f; // 单位:cm
  189. ins.gps_vel = raw_gps._gps_vel * 10; // 单位:cm/s
  190. ins.gps_num = raw_gps._gps_num;
  191. ins.gps_pdop = raw_gps._gps_pdop;
  192. ins.lng = raw_gps._longitude;
  193. ins.lat = raw_gps._latitude;
  194. UTCToLocalTime(8);
  195. // 振动系数
  196. ins.oscillating_coefficient = raw_gps._oscillating_coefficient;
  197. ins.rtk_state = raw_gps._rtk_state;
  198. ins.temprature = raw_gps._temprature;
  199. // 姿态模式标志位,也就是是否可以起飞标志位
  200. ins.insgps_ok = raw_gps._insgps_ok;
  201. // 磁校准状态标志位
  202. ins.mag_calib_flag = raw_gps._state_flag;
  203. ins.imu_conf.filter_param = (raw_gps._imu_assembly_direction >> 4) & 0x0f;
  204. ins.imu_conf.assemble_direction_param = raw_gps._imu_assembly_direction & 0x0f;
  205. ins.imu_conf.dgps_direction_param = raw_gps._dgps_assembly_direction;
  206. // 只有磁校准模式下才来赋值mag_cal_status
  207. if (pilot_mode == PILOT_MAG_CLB)
  208. {
  209. if (ins.mag_calib_flag != MAG_CAL_NO)
  210. {
  211. mag_cal_status = ins.mag_calib_flag;
  212. }
  213. }
  214. }
  215. /**
  216. * @brief dma解析sensor数据
  217. */
  218. void dma_analysis_sensordata(void) {}
  219. /**
  220. * @brief 解析 imu 收到的 vklink 类型消息
  221. *
  222. * @param rxMsg
  223. */
  224. static void _imu_vklink_rx_msg_decode(const VKlink_Msg_Type *rxMsg)
  225. {
  226. switch (imu_rx_msg.compid)
  227. {
  228. /* 如果是 IMU 的数据 */
  229. case 1:
  230. {
  231. imu_link_status = COMP_NORMAL;
  232. if (ins_data_time_sem == 0)
  233. ins_data_time = micros();
  234. switch (imu_rx_msg.msgid)
  235. {
  236. case IMU_MSG_ID:
  237. {
  238. memcpy(&raw_imu, imu_rx_msg.payload, sizeof(raw_imu));
  239. // 中断中需要更新姿态信息
  240. imu_attitude_ananlysis();
  241. // 400hz的姿态环
  242. attitude_pid_ctl_rp(&pid_m_roll, &pid_v_roll);
  243. attitude_pid_ctl_rp(&pid_m_pitch, &pid_v_pitch);
  244. attitude_pid_ctl_yaw(&pid_m_yaw, &pid_v_yaw);
  245. // 400AHZ的内环
  246. rate_control();
  247. // 如果不在电调校准程序
  248. if (pilot_mode == PILOT_NORMAL)
  249. {
  250. if(debug_mode == false)
  251. unlocked_motor_output(); // 写输出到PWM信号。
  252. }
  253. recieve_isimudata = true;
  254. }
  255. break;
  256. case GPS_MSG_ID:
  257. {
  258. memcpy(&raw_gps, imu_rx_msg.payload, sizeof(raw_gps));
  259. recieve_isgpsdata = true;
  260. }
  261. break;
  262. case SENSOR_MSG_ID:
  263. {
  264. memcpy(&raw_sensor, imu_rx_msg.payload, sizeof(raw_sensor));
  265. recieve_issensordata = true;
  266. }
  267. break;
  268. case VER_MSG_ID:
  269. {
  270. get_imu_version = true;
  271. memcpy(&ins.imu_conf.version, &imu_rx_msg.payload[0], 4);
  272. }
  273. break;
  274. case GPS_POS_OFFSET_ID:
  275. {
  276. get_gps_pos_param = true;
  277. for (uint8_t i = 0; i < 6; ++i)
  278. {
  279. ins.imu_conf.gps_pos_param[i] = imu_rx_msg.payload[i];
  280. }
  281. }
  282. break;
  283. case IMU_POS_OFFSET_ID:
  284. {
  285. get_imu_pos_param = true;
  286. for (uint8_t i = 0; i < 3; ++i)
  287. {
  288. ins.imu_conf.imu_pos_param[i] = imu_rx_msg.payload[i];
  289. }
  290. }
  291. break;
  292. case ACK_MSG_ID:
  293. {
  294. uint8_t ack_id = imu_rx_msg.payload[0];
  295. switch (ack_id)
  296. {
  297. case CALIBRARION_MSG_ID:
  298. {
  299. uint8_t calib_id = imu_rx_msg.payload[1];
  300. switch (calib_id)
  301. {
  302. case LOCK_UNLOCK_CALIB:
  303. {
  304. uint8_t id_content = imu_rx_msg.payload[2];
  305. switch (id_content)
  306. {
  307. case LOCKED:
  308. notify_imu_lock = false;
  309. break;
  310. case UNLOCKED:
  311. notify_imu_unlock = false;
  312. break;
  313. }
  314. }
  315. break;
  316. case DISABLE_GPS_ALT:
  317. {
  318. uint8_t id_content = imu_rx_msg.payload[2];
  319. switch (id_content)
  320. {
  321. case 1:
  322. notify_imu_disable_gpsalt = false;
  323. break;
  324. case 0:
  325. notify_imu_enable_gpsalt = false;
  326. break;
  327. default:
  328. break;
  329. }
  330. }
  331. break;
  332. // 姿态清零
  333. case ATTITUE_CALIB:
  334. // euler_angel_need_clear = false;
  335. break;
  336. // 安装方向
  337. case ASSEMBLE_CALIB:
  338. // change_imu_assembly_direction = false;
  339. break;
  340. // 滤波参数
  341. case FILTER_PARAM_CALIB:
  342. // change_imu_filter_param = false;
  343. break;
  344. // 修改双差分天线安装方向
  345. case DGPS_DIRECTION_CALIB:
  346. // change_imu_dgps_direction = false;
  347. break;
  348. // 修改 IMU 安装位置
  349. case GPS_POS_CALIB:
  350. for (uint8_t i = 0; i < 6; ++i)
  351. {
  352. ins.imu_conf.gps_pos_param[i] =
  353. (int8_t)imu_rx_msg.payload[i + 2];
  354. }
  355. break;
  356. case IMU_POS_CALIB:
  357. for (uint8_t i = 0; i < 3; ++i)
  358. {
  359. ins.imu_conf.imu_pos_param[i] =
  360. (int8_t)imu_rx_msg.payload[i + 2];
  361. }
  362. break;
  363. default:
  364. break;
  365. }
  366. }
  367. break;
  368. default:
  369. break;
  370. }
  371. }
  372. break;
  373. default:
  374. break;
  375. }
  376. }
  377. break; /* imu_rx_msg.compid case 1 end */
  378. /* 如果是 IMU BOOTLOADER 的数据 */
  379. case 201:
  380. {
  381. /* 转发给地面站以进行升级 */
  382. if (need_gcs_tx_imu_rx_msg == 0)
  383. {
  384. need_gcs_tx_imu_rx_msg = 1;
  385. memcpy(&gcs_tx_imu_msg, &imu_rx_msg, sizeof(imu_rx_msg));
  386. }
  387. switch (imu_rx_msg.msgid)
  388. {
  389. /* 如果是应答消息,从串口转发出去 */
  390. case 21:
  391. {
  392. uint8_t id_ack = imu_rx_msg.payload[0];
  393. switch (id_ack)
  394. {
  395. /* 如果是应答升级 end 消息,则将飞控退出 IMU 升级模式 */
  396. case 202:
  397. if (pilot_mode == PILOT_IMU_UPDATE)
  398. {
  399. pilot_mode = PILOT_NORMAL;
  400. }
  401. break;
  402. }
  403. }
  404. break;
  405. /* 如果是 bootloader 状态消息 */
  406. case 199:
  407. {
  408. uint8_t id_status = imu_rx_msg.payload[0];
  409. switch (id_status)
  410. {
  411. /* bootloader 状态正常 */
  412. case 0:
  413. if (pilot_mode == PILOT_IMU_UPDATE)
  414. pilot_mode = PILOT_NORMAL;
  415. break;
  416. /* bootloader 没有正常程序,需要升级 */
  417. case 1:
  418. if (pilot_mode != PILOT_IMU_UPDATE)
  419. pilot_mode = PILOT_IMU_UPDATE;
  420. break;
  421. default:
  422. break;
  423. }
  424. }
  425. break;
  426. default:
  427. break;
  428. }
  429. }
  430. break; /* imu_rx_msg.compid case 201 end */
  431. default:
  432. break;
  433. }
  434. }
  435. /**
  436. * @brief imu 接收回调函数
  437. *
  438. * @param pbuffer
  439. * @param rx_length
  440. */
  441. void recv_imu_data_hookfunction(const uint8_t *pbuffer, uint32_t rx_length)
  442. {
  443. int parse_result = 0;
  444. if (pbuffer[0] == 0xFE && pbuffer[1] <= 255)
  445. {
  446. if (crc16_cyc_cal(0xFFFF, (uint8_t *)pbuffer, pbuffer[1] + 8) == 0)
  447. {
  448. parse_result = 1;
  449. imu_rx_msg.head = pbuffer[0];
  450. imu_rx_msg.payload_len = pbuffer[1];
  451. imu_rx_msg.seq = pbuffer[2];
  452. imu_rx_msg.sysid = pbuffer[3];
  453. imu_rx_msg.compid = pbuffer[4];
  454. imu_rx_msg.msgid = pbuffer[5];
  455. memcpy(imu_rx_msg.payload, (uint8_t *)&pbuffer[6],
  456. imu_rx_msg.payload_len);
  457. }
  458. else
  459. {
  460. parse_result = -1;
  461. }
  462. }
  463. if (parse_result == 1)
  464. {
  465. _imu_vklink_rx_msg_decode(&imu_rx_msg);
  466. }
  467. else if (micros() > 10000000 && parse_result == -1)
  468. {
  469. dma_iserror = true;
  470. } /* parse char end */
  471. }
  472. void get_right_ins_data(void)
  473. {
  474. // 处理DMA中的Imu数据
  475. if (recieve_isimudata == true)
  476. {
  477. dma_analysis_imudata();
  478. recieve_isimudata = false;
  479. }
  480. // 处理DMA中的Gps数据
  481. if (recieve_isgpsdata == true)
  482. {
  483. dma_analysis_gpsdata();
  484. recieve_isgpsdata = false;
  485. }
  486. // 处理DMA中的Sensor数据
  487. if (recieve_issensordata == true)
  488. {
  489. dma_analysis_sensordata();
  490. recieve_issensordata = false;
  491. }
  492. }
  493. /**
  494. * @brief 检测 IMU 链接状态
  495. */
  496. void get_ins_status(void)
  497. {
  498. static bool noimu_check_enable = false;
  499. static unsigned int noimu_time = 0;
  500. // 检测到IMU丢失,300ms无数据。
  501. // 中断中更新ins_data_time不加变量锁会出现冲突,出现负值使大于300ms成立。
  502. ins_data_time_sem = 1;
  503. uint32_t ins_data_time_err = micros() - ins_data_time;
  504. ins_data_time_sem = 0;
  505. if (!noimu_check_enable)
  506. {
  507. noimu_check_enable = true;
  508. }
  509. if (ins_data_time_err > 2000000 && imu_link_status == COMP_NORMAL &&
  510. noimu_check_enable)
  511. {
  512. imu_link_status = COMP_LOST;
  513. noimu_time = micros();
  514. }
  515. // IMU丢失后再缓冲200ms时间,如果不能恢复则直接落锁
  516. if (micros() - noimu_time > 100000 && imu_link_status == COMP_LOST)
  517. {
  518. if (thr_lock_status != LOCKED)
  519. {
  520. set_thr_lock_status(LOCKED, NOIMULOCK);
  521. }
  522. }
  523. // 收到IMU数据后闪板载灯
  524. if (imu_link_status == COMP_NORMAL)
  525. {
  526. v8m_yy_led_toggle(V8M_YY_LED_G);
  527. }
  528. else
  529. {
  530. v8m_yy_led_on(V8M_YY_LED_G);
  531. }
  532. // 收到GPS搜星后闪板载灯
  533. if (raw_gps._gps_num > 0 && raw_gps._gps_num <= 5)
  534. {
  535. v8m_yy_led_toggle(V8M_YY_LED_R);
  536. }
  537. else if (raw_gps._gps_num > 5)
  538. {
  539. v8m_yy_led_on(V8M_YY_LED_R);
  540. }
  541. else
  542. {
  543. v8m_yy_led_off(V8M_YY_LED_R);
  544. }
  545. }
  546. void send_vklink_msg_to_imu(const VKlink_Msg_Type *txMsg)
  547. {
  548. uint8_t *tx_buff = USART3_Tx_Buf;
  549. uint32_t tx_len = VKlink_MsgTxFormat(txMsg, tx_buff);
  550. // open_usart3_dma_tx(tx_len);
  551. for (size_t i = 0; i < tx_len; ++i)
  552. {
  553. UART3_Put_Char(tx_buff[i]);
  554. }
  555. }
  556. void send_req_msg_to_imu(uint8_t req_id)
  557. {
  558. VKlink_Msg_Type txMsg;
  559. uint32_t payload_index = 0;
  560. txMsg.head = VKLINK_MSG_HEAD;
  561. txMsg.seq = imu_vklink_sys.tx_seq++;
  562. txMsg.sysid = imu_vklink_sys.sysid;
  563. txMsg.compid = imu_vklink_sys.compid;
  564. txMsg.msgid = REQ_MSG_ID;
  565. txMsg.payload[payload_index++] = req_id;
  566. txMsg.payload[payload_index++] = 0;
  567. txMsg.payload[payload_index++] = 0;
  568. txMsg.payload[payload_index++] = 0;
  569. txMsg.payload_len = payload_index;
  570. send_vklink_msg_to_imu(&txMsg);
  571. }
  572. void send_calibration_msg_to_imu(uint8_t calib_id, uint8_t *calib_value,
  573. uint16_t len)
  574. {
  575. VKlink_Msg_Type txMsg;
  576. uint32_t payload_index = 0;
  577. txMsg.head = VKLINK_MSG_HEAD;
  578. txMsg.seq = imu_vklink_sys.tx_seq++;
  579. txMsg.sysid = imu_vklink_sys.sysid;
  580. txMsg.compid = imu_vklink_sys.compid;
  581. txMsg.msgid = CALIBRARION_MSG_ID;
  582. txMsg.payload[payload_index++] = calib_id;
  583. for (uint16_t i = 0; i < len; ++i)
  584. txMsg.payload[payload_index++] = calib_value[i];
  585. txMsg.payload_len = payload_index;
  586. send_vklink_msg_to_imu(&txMsg);
  587. if (calib_id == GPS_POS_CALIB)
  588. {
  589. get_gps_pos_param = false;
  590. }
  591. if (calib_id == IMU_POS_CALIB)
  592. {
  593. get_imu_pos_param = false;
  594. }
  595. }
  596. // msgid0x20 互定位数据->IMU
  597. void send_imu_hdw_data(uint8_t update_type, void *data)
  598. {
  599. static VKlink_Msg_Type txMsg;
  600. txMsg.head = VKLINK_MSG_HEAD;
  601. txMsg.seq = imu_vklink_sys.tx_seq++;
  602. txMsg.sysid = imu_vklink_sys.sysid;
  603. txMsg.compid = imu_vklink_sys.compid;
  604. txMsg.msgid = HDW_MSG_ID;
  605. #pragma pack(1)
  606. struct imu_hdw_data
  607. {
  608. int16_t x; // dm
  609. int16_t y; // dm
  610. uint16_t z; // dm
  611. uint16_t flag;
  612. int16_t delay_time; // ms
  613. };
  614. struct imu_pos_data
  615. {
  616. int lon; // 1e-7
  617. int lat; // 1e-7
  618. };
  619. struct imu_vel_data
  620. {
  621. int gps_alt_mm; // mm
  622. int16_t gps_vel_mm; // mm/s
  623. int16_t gps_yaw; // 0.1deg
  624. uint8_t fix_status;
  625. uint8_t gps_num;
  626. };
  627. #pragma pack()
  628. switch (update_type)
  629. {
  630. case 0:
  631. {
  632. struct imu_hdw_data *p = (struct imu_hdw_data *)txMsg.payload;
  633. struct imu_hdw_data *pdata = (struct imu_hdw_data *)data;
  634. p->x = pdata->x;
  635. p->y = pdata->y;
  636. p->z = pdata->z;
  637. p->flag = pdata->flag;
  638. p->delay_time = hdw_can_delay;
  639. break;
  640. }
  641. case 1:
  642. {
  643. struct imu_pos_data *p = (struct imu_pos_data *)(txMsg.payload + sizeof(struct imu_hdw_data));
  644. struct imu_pos_data *pdata = (struct imu_pos_data *)data;
  645. p->lon = pdata->lon;
  646. p->lat = pdata->lat;
  647. break;
  648. }
  649. case 2:
  650. {
  651. struct imu_vel_data *p = (struct imu_vel_data *)(txMsg.payload + sizeof(struct imu_hdw_data) + sizeof(struct imu_pos_data));
  652. struct imu_vel_data *pdata = (struct imu_vel_data *)data;
  653. p->gps_alt_mm = pdata->gps_alt_mm;
  654. p->gps_vel_mm = pdata->gps_vel_mm;
  655. p->gps_yaw = pdata->gps_yaw;
  656. p->fix_status = pdata->fix_status;
  657. p->gps_num = pdata->gps_num;
  658. break;
  659. }
  660. case 3:
  661. {
  662. struct imu_hdw_data *p = (struct imu_hdw_data *)txMsg.payload;
  663. int16_t *pdata = (int16_t *)data;
  664. p->delay_time = *pdata;
  665. }
  666. default:
  667. break;
  668. }
  669. txMsg.payload_len = sizeof(struct imu_hdw_data)
  670. /*+ sizeof(struct imu_pos_data) + sizeof(struct imu_vel_data)*/;
  671. send_vklink_msg_to_imu(&txMsg);
  672. }
  673. /**
  674. * @brief 向IMU发送数据
  675. */
  676. void send_msg_to_imu(void)
  677. {
  678. // 记录上一次发送指令的时间
  679. static uint32_t send_imu_time;
  680. // ========== IMU 升级 ==============
  681. if (pilot_mode == PILOT_IMU_UPDATE)
  682. {
  683. }
  684. else
  685. {
  686. // --------- 请求IMU版本 -----------------
  687. if (get_imu_version == false && thr_lock_status == LOCKED &&
  688. micros() > 10000000)
  689. {
  690. if (!usart3_tx_isbusy() && micros() - send_imu_time > 50000)
  691. {
  692. send_req_msg_to_imu(VER_MSG_ID);
  693. send_imu_time = micros();
  694. }
  695. }
  696. // ---------- 请求 GPS 安装位置偏差 ------------
  697. else if (get_gps_pos_param == false && thr_lock_status == LOCKED)
  698. {
  699. if (!usart3_tx_isbusy() && micros() - send_imu_time > 50000)
  700. {
  701. send_req_msg_to_imu(GPS_POS_OFFSET_ID);
  702. send_imu_time = micros();
  703. }
  704. }
  705. // ---------- 请求 IMU 安装位置偏差 ------------
  706. else if (get_imu_pos_param == false && thr_lock_status == LOCKED)
  707. {
  708. if (!usart3_tx_isbusy() && micros() - send_imu_time > 50000)
  709. {
  710. send_req_msg_to_imu(IMU_POS_OFFSET_ID);
  711. send_imu_time = micros();
  712. }
  713. }
  714. // ----------- 磁 校 准 ---------------
  715. else if (ci_jiao_zhun == true && thr_lock_status == LOCKED &&
  716. mag_cal_status == MAG_CAL_NO)
  717. {
  718. if (!usart3_tx_isbusy() && micros() - send_imu_time > 50000)
  719. {
  720. uint8_t calib_data[3] = {0};
  721. send_calibration_msg_to_imu(MAG_CALIB, calib_data, 0);
  722. send_imu_time = micros();
  723. ci_jiao_zhun = false;
  724. // 主动进入磁校准模式
  725. pilot_mode = PILOT_MAG_CLB;
  726. }
  727. }
  728. // ========== 通知 IMU 飞控解锁 =====
  729. else if (notify_imu_unlock == true)
  730. {
  731. if (!usart3_tx_isbusy() && micros() - send_imu_time > 200000)
  732. {
  733. uint8_t calib_value[3] = {1, 0, 0};
  734. send_calibration_msg_to_imu(LOCK_UNLOCK_CALIB, calib_value, 1);
  735. send_imu_time = micros();
  736. }
  737. }
  738. else if (notify_imu_disable_gpsalt)
  739. {
  740. if (!usart3_tx_isbusy() && micros() - send_imu_time > 50000)
  741. {
  742. uint8_t calib_value[3] = {1, 0, 0};
  743. send_calibration_msg_to_imu(DISABLE_GPS_ALT, calib_value, 1);
  744. send_imu_time = micros();
  745. }
  746. }
  747. else if (notify_imu_enable_gpsalt)
  748. {
  749. if (!usart3_tx_isbusy() && micros() - send_imu_time > 50000)
  750. {
  751. uint8_t calib_value[3] = {0, 0, 0};
  752. send_calibration_msg_to_imu(DISABLE_GPS_ALT, calib_value, 1);
  753. send_imu_time = micros();
  754. }
  755. }
  756. }
  757. }
  758. /**
  759. * @brief 对水平位置做窗口均值滤波,窗口宽度80
  760. * @retval none
  761. */
  762. #define POS_FILTER_COUNT 80
  763. char average_filter_counts;
  764. static void horizental_pos_aver_filter(void)
  765. {
  766. static uint8_t position_counts;
  767. static int pos_long_filter_buf[POS_FILTER_COUNT + 1] = {0};
  768. static int pos_lati_filter_buf[POS_FILTER_COUNT + 1] = {0};
  769. static int miss_long_filter_buf[POS_FILTER_COUNT + 1] = {0};
  770. static int miss_lati_filter_buf[POS_FILTER_COUNT + 1] = {0};
  771. // 定点的时候对经纬度做均值滤波,以及丢失的精度的找回
  772. pos_long_filter_buf[POS_FILTER_COUNT] -=
  773. pos_long_filter_buf[position_counts];
  774. pos_long_filter_buf[position_counts] = raw_imu._c_lng / POS_FILTER_COUNT;
  775. pos_long_filter_buf[POS_FILTER_COUNT] +=
  776. pos_long_filter_buf[position_counts];
  777. miss_long_filter_buf[POS_FILTER_COUNT] -=
  778. miss_long_filter_buf[position_counts];
  779. miss_long_filter_buf[position_counts] =
  780. raw_imu._c_lng -
  781. pos_long_filter_buf[position_counts] * POS_FILTER_COUNT;
  782. // miss_long_filter_buf[position_counts] = Longitude_GPS %
  783. // POS_FILTER_COUNT;
  784. miss_long_filter_buf[POS_FILTER_COUNT] +=
  785. miss_long_filter_buf[position_counts];
  786. pos_lati_filter_buf[POS_FILTER_COUNT] -=
  787. pos_lati_filter_buf[position_counts];
  788. pos_lati_filter_buf[position_counts] = raw_imu._c_lat / POS_FILTER_COUNT;
  789. pos_lati_filter_buf[POS_FILTER_COUNT] +=
  790. pos_lati_filter_buf[position_counts];
  791. miss_lati_filter_buf[POS_FILTER_COUNT] -=
  792. miss_lati_filter_buf[position_counts];
  793. miss_lati_filter_buf[position_counts] =
  794. raw_imu._c_lat -
  795. pos_lati_filter_buf[position_counts] * POS_FILTER_COUNT;
  796. // miss_lati_filter_buf[position_counts] = Latitude_GPS %
  797. // POS_FILTER_COUNT;
  798. miss_lati_filter_buf[POS_FILTER_COUNT] +=
  799. miss_lati_filter_buf[position_counts];
  800. position_counts++;
  801. if (position_counts >= POS_FILTER_COUNT)
  802. position_counts = 0;
  803. average_filter_counts++;
  804. if (average_filter_counts >= POS_FILTER_COUNT)
  805. {
  806. average_filter_counts = POS_FILTER_COUNT;
  807. pid_m_posx.loc_c =
  808. pos_long_filter_buf[POS_FILTER_COUNT] +
  809. miss_long_filter_buf[POS_FILTER_COUNT] / POS_FILTER_COUNT;
  810. pid_m_posy.loc_c =
  811. pos_lati_filter_buf[POS_FILTER_COUNT] +
  812. miss_lati_filter_buf[POS_FILTER_COUNT] / POS_FILTER_COUNT;
  813. }
  814. else
  815. {
  816. pid_m_posx.loc_c = raw_imu._c_lng;
  817. pid_m_posy.loc_c = raw_imu._c_lat;
  818. }
  819. }
  820. void unclock_clear_altitude(void)
  821. {
  822. // 清0气压高度
  823. clear_alt_offset = plane_baro_alt + offset_alt;
  824. // 清0积分高度
  825. pid_m_alt.loc_c = 0;
  826. }
  827. /**
  828. * @brief 时间按照时区转换
  829. *
  830. * @param timezone 时区
  831. */
  832. void UTCToLocalTime(int timezone)
  833. {
  834. int year, month, day, hour;
  835. int lastday = 0; // 月的最后一天的日期
  836. int lastlastday = 0; // 上月的最后一天的日期
  837. year = raw_gps._gps_year; // 已知的UTC时间
  838. month = raw_gps._gps_month; // 已知的UTC时间
  839. day = raw_gps._gps_day; // 已知的UTC时间
  840. hour = raw_gps._gps_hour + timezone; // 已知的UTC时间
  841. switch (month)
  842. {
  843. case 1:
  844. case 3:
  845. case 5:
  846. case 7:
  847. case 8:
  848. case 10:
  849. case 12:
  850. lastday = 31;
  851. lastlastday = 30;
  852. if (month == 3)
  853. {
  854. // 判断是否为闰年,年号能被400整除或年号能被4整除,而不能被100整除为闰年
  855. if ((year % 400 == 0) || (year % 4 == 0 && year % 100 != 0))
  856. lastlastday = 29; // 闰年的2月为29天,平年为28天
  857. else
  858. lastlastday = 28;
  859. }
  860. if (month == 8)
  861. lastlastday = 31;
  862. break;
  863. case 4:
  864. case 6:
  865. case 9:
  866. case 11:
  867. lastday = 30;
  868. lastlastday = 31;
  869. break;
  870. case 2:
  871. lastlastday = 31;
  872. if ((year % 400 == 0) ||
  873. (year % 4 == 0 && year % 100 != 0)) // 闰年的2月为29天,平年为28天
  874. lastday = 29;
  875. else
  876. lastday = 28;
  877. break;
  878. default:
  879. break;
  880. }
  881. if (hour >= 24)
  882. { // 当算出的区时大于或等于24:00时,应减去24:00,日期加一天
  883. hour -= 24;
  884. day += 1;
  885. if (day > lastday)
  886. { // 当算出的日期大于该月最后一天时,应减去该月最后一天的日期,月份加上一个月
  887. day -= lastday;
  888. month += 1;
  889. if (month > 12)
  890. { // 当算出的月份大于12时,应减去12,年份加上一年
  891. month -= 12;
  892. year += 1;
  893. }
  894. }
  895. }
  896. if (hour < 0)
  897. { // 当算出的区时为负数时,应加上24:00,日期减一天
  898. hour += 24;
  899. day -= 1;
  900. if (day < 1)
  901. { // 当算出的日期为0时,日期变为上一月的最后一天,月份减去一个月
  902. day = lastlastday;
  903. month -= 1;
  904. if (month < 1)
  905. { // 当算出的月份为0时,月份变为12月,年份减去一年
  906. month = 12;
  907. year -= 1;
  908. }
  909. }
  910. }
  911. // 得到转换后的本地时间
  912. ins.gps_year = year;
  913. ins.gps_month = month;
  914. ins.gps_day = day;
  915. ins.gps_hour = hour;
  916. ins.gps_minute = raw_gps._gps_minute;
  917. if (ins.gps_second != raw_gps._gps_second)
  918. {
  919. ins.gps_second = raw_gps._gps_second;
  920. ins.last_gps_second_local_time = micros();
  921. }
  922. ins.gps_millisecond = raw_gps._gps_millisecond;
  923. }
  924. /**
  925. * @brief 向地面站发送 imu 来的消息
  926. *
  927. */
  928. void imu_tx_msg_to_gcs(struct GCS_Link *pgcs)
  929. {
  930. if (need_gcs_tx_imu_rx_msg == 1)
  931. {
  932. need_gcs_tx_imu_rx_msg = 0;
  933. gs_tx_vklink_msg(pgcs, &gcs_tx_imu_msg);
  934. }
  935. }