loaded_mpc.cpp 17 KB

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