mode_gcs_tax_launch_run.c 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486
  1. #include "mode_gcs_tax_launch_run.h"
  2. #include "auto_pilot.h"
  3. #include "control_attitude.h"
  4. #include "control_rate.h"
  5. #include "control_throttle.h"
  6. #include "euler.h"
  7. #include "helpler_funtions.h"
  8. #include "lowpass_filter.h"
  9. #include "matrix.h"
  10. #include "mode_attitude.h"
  11. #include "my_math.h"
  12. #include "params.h"
  13. #include "pilot_navigation.h"
  14. #include "soft_can_yy.h"
  15. #include "soft_imu.h"
  16. #include "soft_time.h"
  17. #include "soft_voltage.h"
  18. #include "flight_mode.h"
  19. #include "soft_motor_output.h"
  20. #include <math.h>
  21. #include <stdint.h>
  22. uint8_t __mode_state = 0; /* 模式运行阶段 */
  23. uint32_t __time_stamp = 0; /* 定时计数 */
  24. struct yy_hdw_pos
  25. {
  26. uint8_t pos_f; /* m */
  27. uint8_t pos_r;
  28. uint8_t pos_d;
  29. };
  30. /**
  31. * @brief 模式初始化
  32. *
  33. * @return true-初始化成功
  34. */
  35. bool gcs_tax_launch_init(void)
  36. {
  37. __mode_state = __STATE_CHECK_ACC_OVERLOAD;
  38. __time_stamp = micros();
  39. butter2_filter_init(&_cxy.vt_ff_flt[0], 200, 10);
  40. butter2_filter_init(&_cxy.vt_ff_flt[1], 200, 10);
  41. return true;
  42. }
  43. /**
  44. * @brief 检测过载
  45. *
  46. * @param dt 运行周期
  47. */
  48. static void _check_acc_overload_run(float dt)
  49. {
  50. const float acc_overload_thr = 1.0f * 9.8f;
  51. static uint32_t acc_over_load_count = 0;
  52. float acc_norm = 0.01f * sqrtf(raw_imu._x_acc * raw_imu._x_acc +
  53. raw_imu._y_acc * raw_imu._y_acc +
  54. raw_imu._z_acc * raw_imu._z_acc);
  55. if (acc_norm > acc_overload_thr)
  56. {
  57. if (acc_over_load_count++ >= 2)
  58. {
  59. // __mode_state = __STATE_SELF_STABILITY;
  60. // __time_stamp = micros();
  61. }
  62. }
  63. }
  64. /**
  65. * @brief 起飞自稳定
  66. *
  67. * @param dt 运行周期
  68. */
  69. static void _self_stability_run(float dt)
  70. {
  71. if (thr_lock_status == LOCKED)
  72. {
  73. if (micros() - __time_stamp > 0.3f * 1e6) /* 延迟 0.3s 后解锁 */
  74. {
  75. __mode_state = __STATE_LAUNCH_GO;
  76. pid_m_alt.thr_hold = true;
  77. set_thr_lock_status(UNLOCKED, LAUNCHUNLOCK);
  78. set_automode_target_yaw(pid_m_yaw.angle_c);
  79. althold_state = NO_ALT_HOLD;
  80. /* 清除定点积分 */
  81. clear_poshold_i_item(&pid_m_posx);
  82. clear_poshold_i_item(&pid_m_posy);
  83. clear_poshold_i_item(&pid_m_alt);
  84. /* 清除内环积分 */
  85. clear_rate_i_item(&pid_m_roll);
  86. clear_rate_i_item(&pid_m_pitch);
  87. clear_rate_i_item(&pid_m_yaw);
  88. ground_air_status = IN_AIR;
  89. throttle_pidctrl_status = THROTTLE_INAIR_RUNNING;
  90. pid_m_alt.vel_t = pid_m_alt.vel_c;
  91. pid_m_roll.angle_t = 0;
  92. pid_m_pitch.angle_t = 0;
  93. }
  94. }
  95. }
  96. extern void control_xy(struct controller_xy *cxy, float dt);
  97. float record_target_alt = 50 * 100; // cm
  98. float thr_max = 1400.0f; // 限制油门最大为
  99. uint16_t angle_plan_run_cnt = 0;
  100. #define _CXY_0_RATIO (-0.8f) // X轴加速度积分结果的比例系数(经验值,需根据实测调整)
  101. #define _CXY_1_RATIO (-0.8f) // Y轴加速度积分结果的比例系数
  102. #define _HWD_INT_PERIOD (5.0f) // 以5s为积分周期
  103. #define _ROLL_THRESHOLD (5.0f) // ROLL角度阈值(度)
  104. #define _PITCH_THRESHOLD (5.0f) // PITCH角度阈值(度)
  105. #define _ANGLE_PERIOD (3.0f) // 角度变化阈值时间周期(秒)
  106. #define _GO_BACK_TIME_PERIOD (5.0f) // 打反向运动时常
  107. #define _GO_BACK_EULER_ANGLE (15.0f) // 打反向欧拉角阈值(度)
  108. #define START_UP_STATE1_DURATION (2 * 1e6) // 弹起阶段稳定时长
  109. #define YAW_DELAY_AFTER_LAUNCH (6.0f * 1e6) // 起飞后航向控制延迟
  110. #define START_UP_STATE2_THR_RAMP_DURATION (1 * 1e6)
  111. // 启动阶段1给1450油门 3秒后进入策略
  112. #define START_UP_STATE0_THR_MAX (1400.0f) // 弹射阶段0 最大油门
  113. #define START_UP_STATE1_THR_MAX (1430.0f) // 弹起阶段1 最大油门
  114. #define START_UP_STATE2_THR_MAX (1480.0f) // 弹起阶段2 最大油门
  115. typedef enum
  116. {
  117. HDW_STATE_POSITION = 0, // 互定位位置控制
  118. HDW_STATE_ACC_INT , // 加速度积分
  119. HDW_STATE_BACK_EULER, // 打反向欧拉角
  120. HDW_STATE_RECOVER // 恢复阶段
  121. } hdw_state_t;
  122. typedef struct
  123. {
  124. hdw_state_t state;
  125. uint32_t state_enter_t;
  126. // 加速度积分
  127. bool acc_int_active;
  128. uint32_t acc_int_start_t;
  129. float acc_int_x;
  130. float acc_int_y;
  131. // 姿态监控
  132. bool angle_monitor_triggered;
  133. uint32_t angle_over_start_t;
  134. bool roll_triggered;
  135. bool pitch_triggered;
  136. // 反向欧拉
  137. bool euler_dir_set;
  138. int8_t roll_dir; // -1 / 0 / +1
  139. int8_t pitch_dir;
  140. } hdw_ctx_t;
  141. static hdw_ctx_t hdw_ctx = {
  142. .state = HDW_STATE_ACC_INT,
  143. .state_enter_t = 0,
  144. .acc_int_active = false,
  145. .acc_int_start_t = 0,
  146. .acc_int_x = 0.0f,
  147. .acc_int_y = 0.0f,
  148. .angle_monitor_triggered = false,
  149. .angle_over_start_t = 0,
  150. .roll_triggered = false,
  151. .pitch_triggered = false,
  152. .euler_dir_set = false,
  153. .roll_dir = 0,
  154. .pitch_dir = 0,
  155. };
  156. static inline void no_hdw_reset(hdw_ctx_t *ctx)
  157. {
  158. ctx->state = HDW_STATE_ACC_INT;
  159. ctx->state_enter_t = 0;
  160. ctx->acc_int_active = false;
  161. ctx->acc_int_start_t = 0;
  162. ctx->acc_int_x = 0.0f;
  163. ctx->acc_int_y = 0.0f;
  164. ctx->angle_monitor_triggered = false;
  165. ctx->angle_over_start_t = 0;
  166. }
  167. static inline void no_hdw_enter_state(hdw_ctx_t *ctx, hdw_state_t new_state)
  168. {
  169. ctx->state = new_state;
  170. ctx->state_enter_t = micros();
  171. // 状态切换通用清理
  172. ctx->angle_monitor_triggered = false;
  173. ctx->acc_int_active = false;
  174. }
  175. // 无互定位下状态机
  176. static void hdw_run_no_insgps(hdw_ctx_t *ctx, float dt)
  177. {
  178. float ax_cmd = 0.0f;
  179. float ay_cmd = 0.0f;
  180. switch (ctx->state)
  181. {
  182. case HDW_STATE_POSITION:break;
  183. /*================ 1. 加速度积分 =================*/
  184. case HDW_STATE_ACC_INT:
  185. {
  186. if (!ctx->acc_int_active)
  187. {
  188. ctx->acc_int_x = 0;
  189. ctx->acc_int_y = 0;
  190. ctx->acc_int_start_t = micros();
  191. ctx->acc_int_active = true;
  192. }
  193. ctx->acc_int_x += pid_m_posx.acc_c * dt * 0.01f;
  194. ctx->acc_int_y += pid_m_posy.acc_c * dt * 0.01f;
  195. ax_cmd = constrain_float(ctx->acc_int_x * _CXY_0_RATIO, -3.0f, 3.0f);
  196. ay_cmd = constrain_float(ctx->acc_int_y * _CXY_1_RATIO, -3.0f, 3.0f);
  197. // 姿态异常检测
  198. // if ((fabsf(pid_m_roll.angle_t - pid_m_roll.angle_c) > _ROLL_THRESHOLD ||
  199. // fabsf(pid_m_pitch.angle_t - pid_m_pitch.angle_c) > _PITCH_THRESHOLD) )
  200. // {
  201. // if(ctx->angle_monitor_triggered == false)
  202. // {
  203. // ctx->angle_monitor_triggered = true;
  204. // ctx->angle_over_start_t = micros();
  205. // }
  206. // if (micros() - ctx->angle_over_start_t > _ANGLE_PERIOD * 1e6)
  207. // {
  208. // bool roll_over = fabsf(pid_m_roll.angle_t - pid_m_roll.angle_c) > _ROLL_THRESHOLD;
  209. // bool pitch_over = fabsf(pid_m_pitch.angle_t - pid_m_pitch.angle_c) > _PITCH_THRESHOLD;
  210. // ctx->roll_triggered = roll_over;
  211. // ctx->pitch_triggered = pitch_over;
  212. // ctx->euler_dir_set = false;
  213. // angle_plan_run_cnt++;
  214. // no_hdw_enter_state(ctx, HDW_STATE_BACK_EULER);
  215. // }
  216. // }else
  217. // {
  218. // ctx->angle_monitor_triggered = false;
  219. // }
  220. // 周期性重置积分
  221. if (micros() - ctx->acc_int_start_t > _HWD_INT_PERIOD * 1e6)
  222. {
  223. ctx->acc_int_x = 0;
  224. ctx->acc_int_y = 0;
  225. ctx->acc_int_start_t = micros();
  226. }
  227. break;
  228. }
  229. /*================ 2. 打反向欧拉 =================*/
  230. case HDW_STATE_BACK_EULER:
  231. {
  232. ax_cmd = 0.0f;
  233. ay_cmd = 0.0f;
  234. if (!ctx->euler_dir_set)
  235. {
  236. ctx->roll_dir = (pid_m_roll.angle_c > 0) ? 1 : -1;
  237. ctx->pitch_dir = (pid_m_pitch.angle_c > 0) ? 1 : -1;
  238. ctx->euler_dir_set = true;
  239. }
  240. if (micros() - ctx->state_enter_t > _GO_BACK_TIME_PERIOD * 1e6)
  241. {
  242. no_hdw_enter_state(ctx, HDW_STATE_ACC_INT);
  243. }
  244. break;
  245. }
  246. /*================ 3. 恢复 =================*/
  247. case HDW_STATE_RECOVER:
  248. {
  249. if (micros() - ctx->state_enter_t > 1.0f * 1e6) // 以0姿态角持续1秒
  250. {
  251. no_hdw_enter_state(ctx, HDW_STATE_ACC_INT);
  252. }
  253. break;
  254. }
  255. default:
  256. no_hdw_enter_state(ctx, HDW_STATE_ACC_INT);
  257. break;
  258. }
  259. /* 统一输出期望加速度 */
  260. _cxy.at[0] = ax_cmd; // 只有在加速度积分下有用 反向欧拉直接控制欧拉角覆盖期望加速度
  261. _cxy.at[1] = ay_cmd;
  262. }
  263. // 设置反向欧拉角
  264. static void no_hdw_apply_back_euler(hdw_ctx_t *ctx)
  265. {
  266. if (ctx->state != HDW_STATE_BACK_EULER)
  267. return;
  268. if (ctx->roll_triggered)
  269. pid_m_roll.angle_t = -ctx->roll_dir * _GO_BACK_EULER_ANGLE;
  270. else
  271. pid_m_roll.angle_t = 0;
  272. if (ctx->pitch_triggered)
  273. pid_m_pitch.angle_t = -ctx->pitch_dir * _GO_BACK_EULER_ANGLE;
  274. else
  275. pid_m_pitch.angle_t = 0;
  276. }
  277. void __tax_launch_go_run(float dt)
  278. {
  279. const struct yy_can_rx_msg_data *yycan_data = yy_can_rx_data_get();
  280. hdw_ctx_t *hdw_ctx_p = &hdw_ctx;
  281. // start_up_ctx_t *start_up_ctx_p = &start_up_ctx;
  282. /**************************************/
  283. if (pid_m_alt.thr_hold == true)
  284. {
  285. thr_max = START_UP_STATE0_THR_MAX;
  286. if (micros() - __time_stamp > 2.0f * 1e6)
  287. {
  288. pid_m_alt.thr_hold = false;
  289. }
  290. althold_state = NO_ALT_HOLD;
  291. t_roll_last = pid_m_roll.angle_t = 0;
  292. t_pitch_last = pid_m_pitch.angle_t = 0;
  293. _cxy.reset = true;
  294. /*弹射后2秒钟,记录当时的高度,作为自动控制时候的目标高度*/
  295. // record_target_alt = pid_m_alt.loc_c;
  296. record_target_alt = 50 * 100; // 50m高度
  297. no_hdw_enter_state(hdw_ctx_p, HDW_STATE_ACC_INT);
  298. }
  299. else
  300. {
  301. // alt_reached = true;
  302. thr_max = START_UP_STATE2_THR_MAX; // 油门限制1480
  303. hdw_run_no_insgps(hdw_ctx_p, dt); // 无互定位状态机
  304. // 大地系下的期望加速度 _cxy.at[0], _cxy.at[1]
  305. float dcm_z[3] = {_cxy.at[0], _cxy.at[1], GRAVITY_MSS};
  306. Vector_Normalize(dcm_z, 3);
  307. float dcm_y[3] = {0, 1, 0};
  308. dcm_y[2] = -(dcm_z[0] * dcm_y[0] + dcm_z[1] * dcm_y[1]) / dcm_z[2];
  309. Vector_Normalize(dcm_y, 3);
  310. float dcm_x[3] = {0, 0, 0};
  311. Vector_CrossProduct_3D(dcm_y, dcm_z, dcm_x);
  312. float dcm[3][3];
  313. for (int i = 0; i < 3; ++i)
  314. {
  315. dcm[i][0] = dcm_x[i];
  316. dcm[i][1] = dcm_y[i];
  317. dcm[i][2] = dcm_z[i];
  318. }
  319. euler_angle_t euler = {0};
  320. Euler_ByDcm(dcm, &euler);
  321. pid_m_roll.angle_t = apply(euler.roll * RAD_TO_DEG, t_roll_last, 15.0f, dt);
  322. pid_m_pitch.angle_t = apply(euler.pitch * RAD_TO_DEG, t_pitch_last, 15.0f, dt);
  323. // no_hdw_apply_back_euler(hdw_ctx_p); // 打反向欧拉角时 覆盖期望欧拉
  324. t_roll_last = pid_m_roll.angle_t;
  325. t_pitch_last = pid_m_pitch.angle_t;
  326. althold_state = NO_ALT_HOLD;
  327. /********************优先响应高度****************/
  328. // if (!isnan(yycan_data->txgl_alt_sp) && yycan_data->txgl_alt_sp > 0 && yycan_data->txgl_alt_sp <= 100)
  329. // {
  330. // record_target_alt = yycan_data->txgl_alt_sp * 100.0f;
  331. // if(debug_mode == false)
  332. // {
  333. // if (fabsf(yycan_data->txgl_alt_sp * 100 - pid_m_alt.loc_c) < 30.0f)
  334. // {
  335. // updata_cmd_status(ALT_EXECUTE, true);
  336. // updata_cmd_status(ALT_SETTING, false);
  337. // alt_reached = true;
  338. // }
  339. // }
  340. // else
  341. // {
  342. // if(micros() - recv_alt_time > 3 * 1e6 && alt_reached == false)
  343. // {
  344. // updata_cmd_status(ALT_EXECUTE, true);
  345. // updata_cmd_status(ALT_SETTING, false);
  346. // alt_reached = true;
  347. // }
  348. // }
  349. // }
  350. //pid_m_alt.loc_t = record_target_alt;
  351. //float perror_u = (record_target_alt - pid_m_alt.loc_c);
  352. // pid_m_alt.vel_t = constrain_float(perror_u * 0.8f, -100.0f, 100.0f); // 期望速度倍做了限制 -100~100cm/s
  353. // pid_m_alt.vel_t = constrain_float(perror_u * 0.8f, -50.0f, 50.0f); // 期望速度倍做了限制 -50~50cm/s
  354. pid_m_alt.vel_t = 100.0f; // 期望速度80cm/s 以0.8m/s的速度撞击没有那么大的冲击, 加长高油门时间 减小减速油门时间 2:1
  355. /********************高度达到后,相应航向****************/
  356. if(((micros()-__time_stamp) > 6.0f * 1e6))
  357. {
  358. alt_reached = true;
  359. }
  360. if (alt_reached) // 差不多就是4秒达到最高点
  361. {
  362. // 航向到位,更新flag
  363. if (pid_m_yaw.enable_tyaw)
  364. {
  365. set_automode_target_yaw(yycan_data->txgl_yaw_sp);
  366. if (fabsf(wrap_180(pid_m_yaw.angle_c - yycan_data->txgl_yaw_sp)) < 5.0f)
  367. {
  368. updata_cmd_status(YAW_EXECUTE, true);
  369. updata_cmd_status(YAW_SETTING, false);
  370. pid_m_yaw.enable_tyaw = false;
  371. yaw_reached = true;
  372. }
  373. }
  374. }
  375. else
  376. {
  377. t_roll_last = pid_m_roll.angle_t = 0;
  378. t_pitch_last = pid_m_pitch.angle_t = 0;
  379. hdw_ctx_p->acc_int_x = 0; // 上升到最高点之前不进行加速度积分策略
  380. hdw_ctx_p->acc_int_y = 0;
  381. }
  382. /*所有动作暂停指令 实际台子无该指令*/
  383. if ((yycan_data->txgl_drone_cmd & CTL_STOP_CMD_MASK) == CTL_STOP_ACTION)
  384. {
  385. set_automode_target_yaw(wrap_360(pid_m_yaw.angle_c)); // 航向锁定
  386. pid_m_alt.vel_t = 0; // 垂速为0
  387. }
  388. }
  389. Calculate_Target_Az(fast_loop_dt);
  390. }
  391. void gcs_tax_launch_run(float dt)
  392. {
  393. switch (__mode_state)
  394. {
  395. case __STATE_CHECK_ACC_OVERLOAD:
  396. _check_acc_overload_run(dt);
  397. break;
  398. case __STATE_SELF_STABILITY:
  399. _self_stability_run(dt);
  400. break;
  401. case __STATE_LAUNCH_GO:
  402. __tax_launch_go_run(dt);
  403. break;
  404. default:
  405. break;
  406. }
  407. }
  408. void gcs_tax_launch_exit(void)
  409. {
  410. pid_m_alt.thr_hold = false;
  411. }