loaded_mpc.cpp 17 KB

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