loaded_mpc.cpp 16 KB

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