loaded_mpc.cpp 15 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432
  1. //
  2. // Created by zx on 22-12-1.
  3. //
  4. #include "loaded_mpc.h"
  5. #include <chrono>
  6. #include <cppad/cppad.hpp>
  7. #include <cppad/ipopt/solve.hpp>
  8. size_t N = 25; //优化考虑后面多少步
  9. size_t nx = 0;
  10. size_t ny = nx + N;
  11. size_t nth = ny + N;
  12. size_t nv = nth + N;
  13. size_t ndlt = nv + N;
  14. size_t nobs = ndlt + N;
  15. class FG_eval_half_agv {
  16. public:
  17. // Fitted polynomial coefficients
  18. Eigen::VectorXd m_coeffs; //曲线方程
  19. Eigen::VectorXd m_statu; //当前状态
  20. Eigen::VectorXd m_condition; //搜索条件参数
  21. FG_eval_half_agv(Eigen::VectorXd coeffs, Eigen::VectorXd statu, Eigen::VectorXd condition) {
  22. m_coeffs = coeffs;
  23. m_statu = statu;
  24. m_condition = condition;
  25. }
  26. typedef CPPAD_TESTVECTOR(CppAD::AD<double>) ADvector;
  27. void operator()(ADvector &fg, const ADvector &vars) {
  28. fg[0] = 0;
  29. double dt = m_condition[0];
  30. double ref_v = m_condition[1];
  31. double obs_w = m_condition[2];
  32. double obs_h = m_condition[3];
  33. double target_x = m_condition[4];
  34. double target_y = m_condition[5];
  35. double v = m_statu[0];
  36. double delta = m_statu[1];
  37. // Weights for how "important" each cost is - can be tuned
  38. const double y_cost_weight = 1000;
  39. const double th_cost_weight = 4000;
  40. const double v_cost_weight = 5000;
  41. const double vth_cost_weight = 1000;
  42. const double a_cost_weight = 1;
  43. const double ath_cost_weight = 10;
  44. const double obs_distance_weight = 5000.0;
  45. // Cost for CTE, psi error and velocity
  46. for (int t = 0; t < N; t++) {
  47. CppAD::AD<double> xt = vars[nx + t];
  48. CppAD::AD<double> fx = m_coeffs[0] + m_coeffs[1] * xt + m_coeffs[2] * pow(xt, 2) + m_coeffs[3] * pow(xt, 3);
  49. fg[0] += y_cost_weight * CppAD::pow(vars[ny + t] - fx, 2);
  50. //fg[0]+=v_cost_weight*(CppAD::pow(vars[nx+t]-target_x,2)+CppAD::pow(vars[ny+t]-target_y,2));
  51. //目标速度loss
  52. fg[0] += v_cost_weight * CppAD::pow(vars[nv + t] - ref_v, 2);
  53. }
  54. for (int t = 0; t < N - 1; t++) {
  55. //速度,加速度,前轮角 weight loss
  56. fg[0] += vth_cost_weight * CppAD::pow(vars[ndlt + t], 2);
  57. fg[0] += a_cost_weight * CppAD::pow(vars[nv + t + 1] - vars[nv + t], 2);
  58. fg[0] += ath_cost_weight * CppAD::pow(vars[ndlt + t + 1] - vars[ndlt + t], 2);
  59. }
  60. /////////////////////
  61. fg[1 + nx] = vars[nx] - vars[nv] * dt;
  62. fg[1 + ny] = vars[ny];
  63. //CppAD::AD<double> w0=vars[nv]/wheelbase*CppAD::tan(vars[ndlt]);
  64. fg[1 + nth] = vars[nth] - vars[ndlt] * dt;
  65. //位姿约束
  66. for (int t = 1; t < N; t++) {
  67. // State at time t + 1
  68. CppAD::AD<double> x1 = vars[nx + t];
  69. CppAD::AD<double> y1 = vars[ny + t];
  70. CppAD::AD<double> th1 = vars[nth + t];
  71. // State at time t
  72. CppAD::AD<double> x0 = vars[nx + t - 1];
  73. CppAD::AD<double> y0 = vars[ny + t - 1];
  74. CppAD::AD<double> th0 = vars[nth + t - 1];
  75. CppAD::AD<double> v0 = vars[nv + t - 1];
  76. // Setting up the rest of the model constraints
  77. fg[1 + nx + t] = x1 - (x0 + v0 * CppAD::cos(th0) * dt);
  78. fg[1 + ny + t] = y1 - (y0 + v0 * CppAD::sin(th0) * dt);
  79. fg[1 + nth + t] = th1 - (th0 + vars[ndlt + t - 1] * dt);
  80. }
  81. //加速度和dlt约束
  82. fg[1 + nv] = (vars[nv] - v) / dt;
  83. fg[1 + ndlt] = (vars[ndlt] - delta) / dt;
  84. for (int t = 1; t < N; ++t) {
  85. fg[1 + nv + t] = (vars[nv + t] - vars[nv + t - 1]) / dt;
  86. fg[1 + ndlt + t] = (vars[ndlt + t] - vars[ndlt + t - 1]) / dt;
  87. }
  88. if (m_statu.size() == 2 + 16) {
  89. //与障碍物的距离
  90. for (int i = 0; i < 8; ++i) {
  91. double ox = m_statu[2 + i * 2];
  92. double oy = m_statu[2 + i * 2 + 1];
  93. for (int t = 0; t < N; ++t) {
  94. /*第i点的矩形方程为: {[(x-xi)cos(Θi)-(y-yi)sin(Θi)]/1.35}**8 +
  95. * {[(x-xi)sin(Θi)+(y-yi)cos(Θi)]/0.75}**8 = 1.0
  96. *
  97. * */
  98. CppAD::AD<double> ra = (ox - vars[nx + t]) * CppAD::cos(vars[nth + t]) -
  99. (oy - vars[ny + t]) * CppAD::sin(vars[nth + t]);
  100. CppAD::AD<double> rb = (ox - vars[nx + t]) * CppAD::sin(vars[nth + t]) +
  101. (oy - vars[ny + t]) * CppAD::cos(vars[nth + t]);
  102. fg[1 + nobs + N * i + t] = CppAD::pow(ra / obs_w, 8) + CppAD::pow(rb / obs_h, 8);
  103. }
  104. }
  105. }
  106. }
  107. };
  108. LoadedMPC::LoadedMPC(const Pose2d &obs, double obs_w, double obs_h, double min_velocity, double max_velocity) {
  109. min_velocity_ = min_velocity;
  110. max_velocity_ = max_velocity;
  111. obs_relative_pose_ = obs;
  112. obs_w_ = obs_w;
  113. obs_h_ = obs_h;
  114. }
  115. LoadedMPC::~LoadedMPC() {}
  116. MpcError LoadedMPC::solve(Trajectory trajectory, Pose2d target, Eigen::VectorXd statu, MPC_parameter mpc_param,
  117. std::vector<double> &out, Trajectory &select_traj, Trajectory &optimize_trajectory) {
  118. auto start = std::chrono::steady_clock::now();
  119. // State vector holds all current values neede for vars below
  120. Pose2d pose_agv = Pose2d(statu[0], statu[1], statu[2]);
  121. double line_velocity = statu[3];
  122. double wmg = statu[4];
  123. //纠正角速度/线速度,使其满足最小转弯半径
  124. double angular = wmg;
  125. double radius = mpc_param.shortest_radius * (1.0 / sqrt(line_velocity * line_velocity + 1e-10));
  126. if ((line_velocity * line_velocity) / (wmg * wmg + 1e-9) < (radius * radius)) {
  127. angular = fabs(line_velocity) / radius;
  128. if (wmg < 0) angular = -angular;
  129. }
  130. double max_wmg = 0.5 / radius;//fabs(line_velocity) / radius;
  131. std::vector<Pose2d> filte_poses;
  132. if (filte_Path(pose_agv, target, trajectory, filte_poses, 10) == false) {
  133. printf("filte path failed ...\n");
  134. return failed;
  135. }
  136. select_traj = Trajectory(filte_poses);
  137. //将选中点移动到小车坐标系
  138. std::vector<Pose2d> transform_poses;
  139. for (int i = 0; i < filte_poses.size(); i++) {
  140. double x = filte_poses[i].x() - pose_agv.x();
  141. double y = filte_poses[i].y() - pose_agv.y();
  142. transform_poses.push_back(Pose2d(x, y, 0).rotate(-pose_agv.theta()));
  143. }
  144. Eigen::VectorXd coef = fit_path(transform_poses);
  145. //优化
  146. typedef CPPAD_TESTVECTOR(double) Dvector;
  147. //根据当前点和目标点距离,计算目标速度
  148. double ref_velocity = Pose2d::distance(pose_agv, target) / 2.5;
  149. if (ref_velocity < 0.1)
  150. ref_velocity = 0.1;
  151. //目标点与起点的连线 朝向与启动朝向 > M_PI/2.0
  152. Pose2d targetPoseInAGV = Pose2d::relativePose(target, pose_agv);
  153. //std::cout<<"target:"<<target<<", agv:"<<pose_agv<<", relative:"<<targetPoseInAGV<<std::endl;
  154. if (targetPoseInAGV.x() < 0)
  155. ref_velocity = -ref_velocity;
  156. double dt = mpc_param.dt;
  157. //printf("min_v:%f max_v:%f\n",min_velocity_,max_velocity_);
  158. double max_dlt = max_wmg;//5*M_PI/180.0;
  159. double max_acc_line_velocity = mpc_param.acc_velocity;
  160. double max_acc_dlt = mpc_param.acc_angular * M_PI / 180.0;
  161. size_t n_vars = N * 5;
  162. Dvector vars(n_vars);
  163. for (int i = 0; i < n_vars; i++) {
  164. vars[i] = 0.0;
  165. }
  166. Dvector vars_lowerbound(n_vars);
  167. Dvector vars_upperbound(n_vars);
  168. for (int i = 0; i < n_vars; i++) {
  169. vars_lowerbound[i] = -1.0e19;
  170. vars_upperbound[i] = 1.0e19;
  171. }
  172. //// limit v
  173. for (int i = nv; i < nv + N; i++) {
  174. vars_lowerbound[i] = -max_velocity_;
  175. vars_upperbound[i] = max_velocity_;
  176. }
  177. ////limint dlt
  178. for (int i = ndlt; i < ndlt + N; i++) {
  179. vars_lowerbound[i] = -max_dlt;
  180. vars_upperbound[i] = max_dlt;
  181. }
  182. // Lower and upper limits for the constraints
  183. size_t n_constraints = N * 5;
  184. /*
  185. * 障碍物是否进入 碰撞检测范围内
  186. */
  187. float distance = Pose2d::distance(obs_relative_pose_, Pose2d(0, 0, 0));
  188. bool find_obs = false;
  189. if (distance < 20) {
  190. //printf(" mpc find obs ,w=%f,h=%f\n",obs_w_,obs_h_);
  191. find_obs = true;
  192. }
  193. if (find_obs) n_constraints = N * (5 + 8);
  194. Dvector constraints_lowerbound(n_constraints);
  195. Dvector constraints_upperbound(n_constraints);
  196. for (int i = 0; i < n_constraints; i++) {
  197. constraints_lowerbound[i] = 0;
  198. constraints_upperbound[i] = 0;
  199. }
  200. //// acc v
  201. for (int i = nv; i < nv + N; i++) {
  202. constraints_lowerbound[i] = -max_acc_line_velocity;
  203. constraints_upperbound[i] = max_acc_line_velocity;
  204. }
  205. //// acc ndlt
  206. for (int i = ndlt; i < ndlt + N; i++) {
  207. constraints_lowerbound[i] = -max_acc_dlt;
  208. constraints_upperbound[i] = max_acc_dlt;
  209. }
  210. // 与障碍物保持距离的约束
  211. if (find_obs) {
  212. for (int i = nobs; i < nobs + 8 * N; ++i) {
  213. constraints_lowerbound[i] = 1.0;
  214. constraints_upperbound[i] = 1e19;
  215. }
  216. }
  217. //限制最小转弯半径,
  218. /*for(int i=nwmg;i<nwmg+N;++i)
  219. {
  220. constraints_lowerbound[i] = 0;
  221. constraints_upperbound[i] = 1.0/(radius*radius);
  222. }*/
  223. if (line_velocity > max_velocity_) {
  224. line_velocity = max_velocity_;
  225. }
  226. if (line_velocity < -max_velocity_) {
  227. line_velocity = -max_velocity_;
  228. }
  229. if (angular > max_dlt) {
  230. angular = max_dlt;
  231. }
  232. if (angular < -max_dlt) {
  233. angular = -max_dlt;
  234. }
  235. Eigen::VectorXd statu_velocity(2);
  236. if (find_obs) {
  237. statu_velocity = Eigen::VectorXd(2 + 16);
  238. std::vector<Pose2d> vertexs = Pose2d::generate_rectangle_vertexs(obs_relative_pose_, obs_w_ * 2, obs_h_ * 2);
  239. for (int i = 0; i < vertexs.size(); ++i) {
  240. //std::cout<<"vetex:"<<vertexs[i]<<std::endl;
  241. statu_velocity[2 + i * 2] = vertexs[i].x();
  242. statu_velocity[2 + i * 2 + 1] = vertexs[i].y();
  243. }
  244. }
  245. statu_velocity[0] = line_velocity;
  246. statu_velocity[1] = angular;
  247. Eigen::VectorXd condition(6);
  248. condition << dt, ref_velocity, obs_w_, obs_h_, targetPoseInAGV.x(), targetPoseInAGV.y();
  249. FG_eval_half_agv fg_eval(coef, statu_velocity, condition);
  250. // options for IPOPT solver
  251. std::string options;
  252. // Uncomment this if you'd like more print information
  253. options += "Integer print_level 0\n";
  254. options += "Sparse true forward\n";
  255. options += "Sparse true reverse\n";
  256. options += "Numeric max_cpu_time 0.5\n";
  257. // place to return solution
  258. CppAD::ipopt::solve_result<Dvector> solution;
  259. // solve the problem
  260. CppAD::ipopt::solve<Dvector, FG_eval_half_agv>(
  261. options, vars, vars_lowerbound, vars_upperbound, constraints_lowerbound,
  262. constraints_upperbound, fg_eval, solution);
  263. auto now = std::chrono::steady_clock::now();
  264. auto duration = std::chrono::duration_cast<std::chrono::microseconds>(now - start);
  265. double time =
  266. double(duration.count()) * std::chrono::microseconds::period::num / std::chrono::microseconds::period::den;
  267. solution.status == CppAD::ipopt::solve_result<Dvector>::success; // invalid_number_detected
  268. if (solution.status != CppAD::ipopt::solve_result<Dvector>::success) {
  269. printf(" mpc failed statu : %d input: %.4f %.5f(%.5f) max_v:%f\n", solution.status, line_velocity,
  270. wmg, angular, max_velocity_);
  271. if (solution.status == CppAD::ipopt::solve_result<Dvector>::local_infeasibility)
  272. return no_solution;
  273. return failed;
  274. }
  275. // Cost
  276. auto cost = solution.obj_value;
  277. out.clear();
  278. double solve_velocity = solution.x[nv];
  279. double solve_angular = solution.x[ndlt];
  280. //纠正角速度/线速度,使其满足最小转弯半径
  281. double correct_angular = solve_angular;
  282. if ((solve_velocity * solve_velocity) / (solve_angular * solve_angular + 1e-9) < (radius * radius)) {
  283. correct_angular = fabs(line_velocity) / radius;
  284. if (solve_angular < 0) correct_angular = -correct_angular;
  285. }
  286. ///-----
  287. printf("input:%.4f %.5f(%.5f) output:%.4f %.5f(%.5f) ref:%.3f max_v:%f time:%.3f\n",
  288. line_velocity, wmg, angular, solve_velocity, solve_angular, correct_angular,
  289. ref_velocity, max_velocity_, time);
  290. /*if(solve_velocity>=0 && solve_velocity<min_velocity_)
  291. solve_velocity=min_velocity_;
  292. if(solve_velocity<0 && solve_velocity>-min_velocity_)
  293. solve_velocity=-min_velocity_;*/
  294. out.push_back(solve_velocity);
  295. out.push_back(correct_angular);
  296. //计算预测轨迹
  297. optimize_trajectory.clear();
  298. for (int i = 0; i < N; ++i) {
  299. Pose2d pose(solution.x[nx + i], solution.x[ny + i], solution.x[nth + i]);
  300. optimize_trajectory.push_point(pose_agv + pose.rotate(pose_agv.theta()));
  301. }
  302. return success;
  303. }
  304. bool LoadedMPC::filte_Path(const Pose2d &point, Pose2d target, Trajectory trajectory,
  305. std::vector<Pose2d> &poses, int point_num) {
  306. double gradient = 0;
  307. if (fabs((target - point).x()) == 0)
  308. gradient = 200.0;
  309. else
  310. gradient = (target - point).y() / (target - point).x();
  311. double theta = gradient2theta(gradient, target.x() - point.x() >= 0);
  312. if (trajectory.size() < 2)
  313. return false;
  314. poses.clear();
  315. for (int i = 0; i < trajectory.size(); i++) {
  316. // 平移加反向旋转到小车坐标系
  317. Pose2d offset = trajectory[i] - point;
  318. double x = offset.x();
  319. double y = offset.y();
  320. double trans_x = x * cos(-theta) - y * sin(-theta);
  321. double trans_y = x * sin(-theta) + y * cos(-theta);
  322. if (trans_x >= 0 && poses.size() < point_num) {
  323. // 旋转到原坐标系
  324. float nx = trans_x * cos(theta) - trans_y * sin(theta);
  325. float ny = trans_x * sin(theta) + trans_y * cos(theta);
  326. Pose2d pose(nx + point.x(), ny + point.y(), trajectory[i].theta());
  327. poses.push_back(pose);
  328. }
  329. }
  330. int size = poses.size();
  331. if (size < point_num) {
  332. //一个点都没有,则以当前点开始,反向取点
  333. float dl = -0.1;
  334. Pose2d last = point;
  335. if (size >= 1) {
  336. //从最后点到最后一点均匀选取
  337. last = poses[size - 1]; //
  338. dl = 0.1;
  339. }
  340. float dx = cos(last.theta()) * dl;
  341. float dy = sin(last.theta()) * dl;
  342. for (int i = 1; i < point_num - size + 1; ++i)
  343. poses.push_back(Pose2d(last.x() + dx * i, last.y() + dy * i, last.theta()));
  344. }
  345. return true;
  346. }
  347. Eigen::VectorXd LoadedMPC::fit_path(const std::vector<Pose2d> &trajectory) {
  348. int order = 3;
  349. assert(order >= 1 && order <= trajectory.size() - 1);
  350. Eigen::MatrixXd A(trajectory.size(), order + 1);
  351. Eigen::VectorXd yvals(trajectory.size());
  352. for (int i = 0; i < trajectory.size(); i++) {
  353. A(i, 0) = 1.0;
  354. yvals[i] = trajectory[i].y();
  355. }
  356. for (int j = 0; j < trajectory.size(); j++) {
  357. for (int i = 0; i < order; i++) {
  358. A(j, i + 1) = A(j, i) * trajectory[j].x();
  359. }
  360. }
  361. auto Q = A.householderQr();
  362. auto result = Q.solve(yvals);
  363. return result;
  364. }