rotate_mpc.cpp 9.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257
  1. //
  2. // Created by gf on 23-7-21.
  3. //
  4. #include "rotate_mpc.h"
  5. #include <chrono>
  6. #include <cppad/cppad.hpp>
  7. #include <cppad/ipopt/solve.hpp>
  8. size_t mpc_rotate_steps = 20; //优化考虑后面多少步
  9. size_t mpc_rotate_delay = 0; // 发送到执行的延迟,即几个周期的时间
  10. size_t mpc_rotate_down_count = 3;//下发前多少步
  11. #define N mpc_rotate_steps
  12. #define delay mpc_rotate_delay
  13. #define down_count mpc_rotate_down_count
  14. class FG_eval_rotate {
  15. public:
  16. Eigen::VectorXd m_statu; //当前状态
  17. Eigen::VectorXd m_condition; //搜索条件参数
  18. FG_eval_rotate(Eigen::VectorXd status, Eigen::VectorXd condition) {
  19. m_statu = status;
  20. m_condition = condition;
  21. }
  22. typedef CPPAD_TESTVECTOR(CppAD::AD<double>) ADvector;
  23. void operator()(ADvector &fg, const ADvector &vars) {
  24. fg[0] = 0;
  25. double dt = m_condition[0];
  26. double target_theta = m_condition[1];
  27. double obs_w = m_condition[2];
  28. double obs_h = m_condition[3];
  29. double angular_velocity = m_statu[0];
  30. // Weights for how "important" each cost is - can be tuned
  31. const double y_cost_weight = 1000;
  32. const double angular_cost_weight = 4000;
  33. const double v_cost_weight = 5000;
  34. const double angular_velocity_cost_weight = 1000;
  35. const double acceleration_cost_weight = 1;
  36. const double angular_acceleration_cost_weight = 10;
  37. const double obs_distance_weight = 5000.0;
  38. // 代价函数计算
  39. for (int t = 0; t < N - 1; ++t) {
  40. /// 角速度,角加速度weight loss
  41. fg[0] += angular_velocity_cost_weight * CppAD::pow(vars[N + t], 2);
  42. fg[0] += angular_acceleration_cost_weight * CppAD::pow(vars[N + t + 1] - vars[N + t], 2);
  43. /// 目标角度 loss
  44. fg[0] += angular_cost_weight * CppAD::pow(target_theta - vars[t], 2);
  45. }
  46. // 约束条件
  47. int n_angular = 1;
  48. int n_angular_acceleration = n_angular + N;
  49. int n_obs = n_angular_acceleration + N;
  50. /// 角度等式约束 1~N
  51. fg[n_angular] = vars[0] - angular_velocity * dt;
  52. for (int t = 1; t < N; ++t) {
  53. // State at time t + 1
  54. CppAD::AD<double> theta1 = vars[t];
  55. // State at time t
  56. CppAD::AD<double> theta0 = vars[t - 1];
  57. CppAD::AD<double> angular_velocity0 = vars[N + t - 1];
  58. // Setting up the rest of the model constraints
  59. fg[n_angular + t] = theta1 - (theta0 + angular_velocity0 * dt);
  60. }
  61. /// 角加速度等式约束 N+1~2N
  62. fg[n_angular_acceleration] = (vars[0 + N] - angular_velocity) / dt;
  63. for (int t = 1; t < N; ++t) {
  64. fg[n_angular_acceleration + t] = (vars[t + N] - vars[t + N - 1]) / dt;
  65. }
  66. /// 障碍物距离等式约束 2N+1~3N
  67. if (m_statu.size() == 1 + 3) {
  68. float obs_x = m_statu[1];
  69. float obs_y = m_statu[2];
  70. float obs_theta = m_statu[3];
  71. Pose2d obs_relative_pose(obs_x, obs_y, obs_theta);
  72. std::vector<Pose2d> obs_vertexes = Pose2d::generate_rectangle_vertexs(obs_relative_pose, obs_w * 2,
  73. obs_h * 2);
  74. for (auto t = 0; t < N; ++t) {
  75. CppAD::AD<double> min_distance = 1e19;
  76. for (auto i = 0; i < 8; ++i) {
  77. CppAD::AD<double> ra = obs_vertexes[i].x() * CppAD::cos(vars[t]) -
  78. obs_vertexes[i].y() * CppAD::sin(vars[t]);
  79. CppAD::AD<double> rb = obs_vertexes[i].x() * CppAD::sin(vars[t]) +
  80. obs_vertexes[i].y() * CppAD::cos(vars[t]);
  81. CppAD::AD<double> distance = CppAD::pow(ra / obs_w, 8) + CppAD::pow(rb / obs_h, 8);
  82. if (distance < min_distance) min_distance = distance;
  83. }
  84. fg[n_obs + t] = min_distance;
  85. }
  86. // std::cout << " fg[n_obs]: " << fg[n_obs] << " | __LINE__:" << __LINE__ << std::endl;
  87. }
  88. }
  89. };
  90. RotateMPC::RotateMPC(const Pose2d &obs, double obs_w, double obs_h, double min_velocity, double max_velocity) {
  91. min_velocity_ = min_velocity;
  92. max_velocity_ = max_velocity;
  93. obs_relative_pose_ = obs;
  94. obs_w_ = obs_w;
  95. obs_h_ = obs_h;
  96. }
  97. RotateMPC::~RotateMPC() {}
  98. MpcError
  99. RotateMPC::solve(Pose2d current_to_target, Eigen::VectorXd statu, MPC_parameter mpc_param, std::vector<double> &out) {
  100. auto start = std::chrono::steady_clock::now();
  101. // State vector holds all current values needed for vars below
  102. Pose2d pose_agv = Pose2d(statu[0], statu[1], statu[2]);
  103. double line_velocity = statu[3];
  104. double angular_velocity = statu[4];
  105. /// 定义最大最小角度,角速度,角加速度(不区分方向)
  106. double max_angular = M_PI;
  107. // double max_angular_velocity = max_velocity_ / (1 + exp(-10 * fabs(current_to_target.theta()) - 0.1));
  108. double max_angular_velocity = max_velocity_ / (1 + exp(-4 * (fabs(current_to_target.theta()) - 0.57*max_velocity_)));
  109. double min_angular_velocity = min_velocity_ ;
  110. double max_angular_acceleration_velocity = mpc_param.acc_angular/ (1 + exp(-7 * (fabs(current_to_target.theta()) + 0.1*mpc_param.acc_angular)));
  111. //double max_angular_acceleration_velocity=0.44;///(1+exp(-36.*(angular_velocity-0.15)))+0.085;
  112. /// 调整输入
  113. if (angular_velocity > max_angular_velocity) angular_velocity = max_angular_velocity;
  114. if (angular_velocity < -max_angular_velocity) angular_velocity = -max_angular_velocity;
  115. // 优化
  116. typedef CPPAD_TESTVECTOR(double) Dvector;
  117. /// 步长
  118. double dt = mpc_param.dt;
  119. /// 初始化参数
  120. size_t n_vars = N * 2; // 0-N为角度,N-2N为角速度
  121. Dvector vars(n_vars); // 0-N为角度,N-2N为角速度
  122. for (int i = 0; i < n_vars; i++) vars[i] = 0.0;
  123. // 参数上下限
  124. Dvector vars_lowerbound(n_vars);
  125. Dvector vars_upperbound(n_vars);
  126. for (int i = 0; i < n_vars; ++i) {
  127. vars_lowerbound[i] = -1.0e19;
  128. vars_upperbound[i] = 1.0e19;
  129. }
  130. /// limit of angular velocity
  131. for (auto i = N; i < 2 * N; ++i) {
  132. vars_lowerbound[i] = -max_angular_velocity;
  133. vars_upperbound[i] = max_angular_velocity;
  134. }
  135. // Lower and upper limits for the constraints
  136. /// 障碍物是否进入 碰撞检测范围内
  137. // float distance = Pose2d::distance(obs_relative_pose_, Pose2d(0, 0, 0));
  138. float distance = 1000;//屏蔽障碍物
  139. bool find_obs = distance < 5;
  140. if (find_obs) printf(" find obs ..............................\n");
  141. size_t n_constraints = 2 * N + find_obs * N;// 0~N角度约束,N~2N角加速度约束, 2N~3N障碍物约束
  142. Dvector constraints_lowerbound(n_constraints);
  143. Dvector constraints_upperbound(n_constraints);
  144. for (auto i = 0; i < n_constraints; ++i) {
  145. constraints_lowerbound[i] = 0;
  146. constraints_upperbound[i] = 0;
  147. }
  148. /// limit of angular acceleration
  149. for (auto i = N; i < 2 * N; ++i) {
  150. //延迟处理,前delay个周期内认定为匀速运动(加速度为0)
  151. if (i < N + delay) {
  152. constraints_lowerbound[i] = 0;
  153. constraints_upperbound[i] = 0;
  154. } else{
  155. constraints_lowerbound[i] = -max_angular_acceleration_velocity;
  156. constraints_upperbound[i] = max_angular_acceleration_velocity;
  157. }
  158. }
  159. /// limit of obs distance
  160. if (find_obs)
  161. for (auto i = 2 * N; i < 3 * N; ++i) {
  162. constraints_lowerbound[i] = 1.0;
  163. constraints_upperbound[i] = 1e19;
  164. }
  165. // fg_eval for IPOPT solver
  166. size_t n_fg_status = 1 + 3 * find_obs;
  167. Eigen::VectorXd fg_status(n_fg_status);
  168. fg_status[0] = angular_velocity;
  169. if (find_obs) {
  170. fg_status[1] = obs_relative_pose_.x();
  171. fg_status[2] = obs_relative_pose_.y();
  172. fg_status[3] = obs_relative_pose_.theta();
  173. }
  174. // std::cout << " size of fg_status: " << fg_status.size() << " | __LINE__: " << __LINE__ << std::endl;
  175. Pose2d targetAngularInAGV = current_to_target;
  176. Eigen::VectorXd condition(4);
  177. condition << dt, targetAngularInAGV.theta(), obs_w_, obs_h_;
  178. FG_eval_rotate fg_eval(fg_status, condition);
  179. // options for IPOPT solver
  180. std::string options;
  181. /// Uncomment this if you'd like more print information
  182. options += "Integer print_level 0\n";
  183. options += "Sparse true forward\n";
  184. options += "Sparse true reverse\n";
  185. options += "Numeric max_cpu_time 0.5\n";
  186. // place to return solution
  187. CppAD::ipopt::solve_result<Dvector> solution;
  188. // solve the problem
  189. CppAD::ipopt::solve<Dvector, FG_eval_rotate>(
  190. options, vars, vars_lowerbound, vars_upperbound, constraints_lowerbound,
  191. constraints_upperbound, fg_eval, solution);
  192. auto now = std::chrono::steady_clock::now();
  193. auto duration = std::chrono::duration_cast<std::chrono::microseconds>(now - start);
  194. double time =
  195. double(duration.count()) * std::chrono::microseconds::period::num / std::chrono::microseconds::period::den;
  196. // invalid_number_detected
  197. if (solution.status != CppAD::ipopt::solve_result<Dvector>::success) {
  198. printf(" mpc failed status : %d input: %.5f max_wmg:%.5f\n", solution.status,
  199. angular_velocity, max_angular_velocity);
  200. if (solution.status == CppAD::ipopt::solve_result<Dvector>::local_infeasibility)
  201. return no_solution;
  202. return failed;
  203. }
  204. // Cost
  205. auto cost = solution.obj_value;
  206. // 输出第一步的角速度
  207. out.clear();
  208. double solve_angular_velocity;
  209. for (int i = 0; i < down_count; ++i) {
  210. solve_angular_velocity = solution.x[i + N + delay];
  211. out.push_back(solve_angular_velocity);
  212. // printf("P[%d]: %f\n", i, solve_angular_velocity);
  213. }
  214. return success;
  215. }