soft_imu.c 29 KB

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