loaded_mpc.cpp 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415
  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 = 20; //优化考虑后面多少步
  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. size_t nwmg=nobs+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 v=m_statu[0];
  33. double delta=m_statu[1];
  34. double obs_x=m_statu[2];
  35. double obs_y=m_statu[3];
  36. double obs_distance=sqrt(obs_x*obs_x+obs_y*obs_y);
  37. // Reference State Cost
  38. // Below defines the cost related the reference state and
  39. // any anything you think may be beneficial.
  40. // Weights for how "important" each cost is - can be tuned
  41. const double y_cost_weight = 5000;
  42. const double th_cost_weight = 4000;
  43. const double v_cost_weight = 1000;
  44. const double vth_cost_weight = 1000;
  45. const double a_cost_weight = 1;
  46. const double ath_cost_weight=100;
  47. const double obs_distance_weight=1000.0;
  48. // Cost for CTE, psi error and velocity
  49. for (int t = 0; t < N; t++) {
  50. CppAD::AD<double> xt=vars[nx+t];
  51. CppAD::AD<double> fx = m_coeffs[0] + m_coeffs[1] * xt + m_coeffs[2] * pow(xt, 2) + m_coeffs[3] * pow(xt, 3);
  52. fg[0] += y_cost_weight * CppAD::pow(vars[ny+t]-fx, 2);
  53. //朝向loss
  54. CppAD::AD<double> fth = CppAD::atan(m_coeffs[1] + 2*m_coeffs[2]*xt + 3*m_coeffs[3]*pow(xt,2));
  55. fg[0] += th_cost_weight * CppAD::pow(vars[nth + t]-fth, 2);
  56. //目标速度loss
  57. fg[0]+=v_cost_weight*CppAD::pow(vars[nv+t]-ref_v,2);
  58. //loss 加上车位姿与障碍物的距离
  59. /*if(obs_distance<4.0)
  60. fg[0]+=obs_distance_weight*(16.0-(CppAD::pow(vars[nx+t]-obs_x,2)));*/
  61. }
  62. // Costs for steering (delta) and acceleration (a)
  63. for (int t = 0; t < N-1; t++) {
  64. //速度,加速度,前轮角 weight loss
  65. fg[0] += vth_cost_weight * CppAD::pow(vars[ndlt+t], 2);
  66. fg[0] += a_cost_weight * CppAD::pow(vars[nv + t+1]-vars[nv+t], 2);
  67. fg[0] += ath_cost_weight * CppAD::pow(vars[ndlt+t+1]-vars[ndlt+t], 2);
  68. }
  69. /////////////////////
  70. fg[1 + nx] = vars[nx]-vars[nv]*dt;
  71. fg[1 + ny] = vars[ny];
  72. //CppAD::AD<double> w0=vars[nv]/wheelbase*CppAD::tan(vars[ndlt]);
  73. fg[1 + nth] = vars[nth]-vars[ndlt]*dt;
  74. //位姿约束
  75. for (int t = 1; t < N; t++) {
  76. // State at time t + 1
  77. CppAD::AD<double> x1 = vars[nx + t];
  78. CppAD::AD<double> y1 = vars[ny + t];
  79. CppAD::AD<double> th1 = vars[nth + t];
  80. // State at time t
  81. CppAD::AD<double> x0 = vars[nx + t -1];
  82. CppAD::AD<double> y0 = vars[ny + t -1];
  83. CppAD::AD<double> th0 = vars[nth + t-1];
  84. CppAD::AD<double> v0 = vars[nv + t-1];
  85. //CppAD::AD<double> w_0=vars[nv+t-1]/wheelbase*CppAD::tan(vars[ndlt+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. {
  96. fg[1+nv+t]=(vars[nv+t]-vars[nv+t-1])/dt;
  97. fg[1+ndlt+t]=(vars[ndlt+t]-vars[ndlt+t-1])/dt;
  98. }
  99. //与障碍物的距离
  100. for(int t=0;t<N;++t)
  101. {
  102. fg[1+nobs+t]=CppAD::pow(vars[nx+t]-obs_x,2)+CppAD::pow(vars[ny+t]-obs_y,2);
  103. }
  104. //转弯半径
  105. /*for(int t=0;t<N;++t)
  106. {
  107. fg[1+nwmg+t]=CppAD::pow(vars[ndlt+t],2)/(CppAD::pow(vars[nv+t],2)+1e-10);
  108. }*/
  109. }
  110. };
  111. LoadedMPC::LoadedMPC(const Pose2d& obs,double min_velocity,double max_velocity){
  112. min_velocity_=min_velocity;
  113. max_velocity_=max_velocity;
  114. obs_relative_pose_=obs;
  115. }
  116. LoadedMPC::~LoadedMPC(){}
  117. bool LoadedMPC::solve(const Trajectory& trajectory, const Pose2d& target,Eigen::VectorXd statu,
  118. std::vector<double>& out,Trajectory& select_traj,Trajectory& optimize_trajectory)
  119. {
  120. auto start=std::chrono::steady_clock::now();
  121. // State vector holds all current values neede for vars below
  122. Pose2d pose_agv = Pose2d(statu[0], statu[1], statu[2]);
  123. double line_velocity = statu[3];
  124. double wmg = statu[4];
  125. //纠正角速度/线速度,使其满足最小转弯半径
  126. double angular=wmg;
  127. double radius=20.0*1.3 * (1.0/sqrt(line_velocity*line_velocity+1e-10));
  128. if( (line_velocity*line_velocity)/(wmg*wmg+1e-9) < (radius*radius)) {
  129. angular = fabs(line_velocity) / radius;
  130. if (wmg < 0) angular = -angular;
  131. }
  132. double max_wmg=0.5/radius;//fabs(line_velocity) / radius;
  133. std::vector<Pose2d> filte_poses;
  134. if (filte_Path(pose_agv, target, trajectory, filte_poses, 10) == false)
  135. {
  136. printf( "filte path failed ...\n");
  137. return false;
  138. }
  139. select_traj= Trajectory(filte_poses);
  140. //将选中点移动到小车坐标系
  141. std::vector<Pose2d> transform_poses;
  142. for (int i = 0; i < filte_poses.size(); i++)
  143. {
  144. double x = filte_poses[i].x() - pose_agv.x();
  145. double y = filte_poses[i].y() - pose_agv.y();
  146. transform_poses.push_back(Pose2d(x,y,0).rotate(-pose_agv.theta()));
  147. }
  148. Eigen::VectorXd coef = fit_path(transform_poses);
  149. //优化
  150. bool ok = true;
  151. typedef CPPAD_TESTVECTOR(double) Dvector;
  152. //根据当前点和目标点距离,计算目标速度
  153. double ref_velocity = Pose2d::distance(pose_agv, target) / 2.5;
  154. if(ref_velocity<0.05)
  155. ref_velocity=0.05;
  156. //目标点与起点的连线 朝向与启动朝向 > M_PI/2.0
  157. Pose2d targetPoseInAGV=Pose2d::relativePose(target,pose_agv);
  158. //std::cout<<"target:"<<target<<", agv:"<<pose_agv<<", relative:"<<targetPoseInAGV<<std::endl;
  159. if(targetPoseInAGV.x()<0)
  160. ref_velocity = -ref_velocity;
  161. double dt = 0.1;
  162. //printf("min_v:%f max_v:%f\n",min_velocity_,max_velocity_);
  163. double max_dlt=max_wmg;//5*M_PI/180.0;
  164. double max_acc_line_velocity=0.5;
  165. double max_acc_dlt=10.*M_PI/180.0;
  166. size_t n_vars = N * 5;
  167. Dvector vars(n_vars);
  168. for (int i = 0; i < n_vars; i++)
  169. {
  170. vars[i] = 0.0;
  171. }
  172. Dvector vars_lowerbound(n_vars);
  173. Dvector vars_upperbound(n_vars);
  174. for (int i = 0; i < n_vars; i++)
  175. {
  176. vars_lowerbound[i] = -1.0e19;
  177. vars_upperbound[i] = 1.0e19;
  178. }
  179. //// limit v
  180. for (int i = nv; i < nv + N; i++)
  181. {
  182. vars_lowerbound[i] = -max_velocity_;
  183. vars_upperbound[i] = max_velocity_;
  184. }
  185. ////limint dlt
  186. for (int i = ndlt; i < ndlt + N; i++)
  187. {
  188. vars_lowerbound[i] = -max_dlt;
  189. vars_upperbound[i] = max_dlt;
  190. }
  191. // Lower and upper limits for the constraints
  192. size_t n_constraints = N * (5+1);
  193. Dvector constraints_lowerbound(n_constraints);
  194. Dvector constraints_upperbound(n_constraints);
  195. for (int i = 0; i < n_constraints; i++)
  196. {
  197. constraints_lowerbound[i] = 0;
  198. constraints_upperbound[i] = 0;
  199. }
  200. //// acc v
  201. for (int i = nv; i < nv + N; i++)
  202. {
  203. constraints_lowerbound[i] = -max_acc_line_velocity;
  204. constraints_upperbound[i] = max_acc_line_velocity;
  205. }
  206. //// acc ndlt
  207. for (int i = ndlt; i < ndlt + N; i++)
  208. {
  209. constraints_lowerbound[i] = -max_acc_dlt;
  210. constraints_upperbound[i] = max_acc_dlt;
  211. }
  212. // 与障碍物保持距离
  213. double dobs=2.2;
  214. for(int i=nobs;i<nobs+N;++i)
  215. {
  216. constraints_lowerbound[i] = dobs*dobs;//pow(float(nobs+N-i)/float(N)*dobs,2);
  217. constraints_upperbound[i] = 1e19;
  218. }
  219. //限制最小转弯半径,
  220. /*for(int i=nwmg;i<nwmg+N;++i)
  221. {
  222. constraints_lowerbound[i] = 0;
  223. constraints_upperbound[i] = 1.0/(radius*radius);
  224. }*/
  225. Eigen::VectorXd statu_velocity(4);
  226. if(line_velocity>max_velocity_)
  227. {
  228. line_velocity=max_velocity_;
  229. //printf(" input +v limited\n");
  230. }
  231. if(line_velocity<-max_velocity_)
  232. {
  233. line_velocity=-max_velocity_;
  234. //printf(" input -v limited\n");
  235. }
  236. if(angular>max_dlt)
  237. {
  238. angular = max_dlt;
  239. printf(" input +dlt limited\n");
  240. }
  241. if(angular<-max_dlt)
  242. {
  243. angular = -max_dlt;
  244. printf(" input -dlt limited\n");
  245. }
  246. statu_velocity << line_velocity, angular,obs_relative_pose_.x(),obs_relative_pose_.y();
  247. Eigen::VectorXd condition(2);
  248. condition << dt, ref_velocity;
  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 = double(duration.count()) * std::chrono::microseconds::period::num / std::chrono::microseconds::period::den;
  266. ok &= solution.status == CppAD::ipopt::solve_result<Dvector>::success;
  267. if (ok == false)
  268. {
  269. printf(" mpc failed statu : %d input: %.4f %.5f(%.5f) relative:(%f,%f) \n",solution.status,line_velocity,
  270. wmg,angular,obs_relative_pose_.x(),obs_relative_pose_.y());
  271. return false;
  272. }
  273. // Cost
  274. auto cost = solution.obj_value;
  275. out.clear();
  276. double solve_velocity=solution.x[nv];
  277. double solve_angular=solution.x[ndlt];
  278. //纠正角速度/线速度,使其满足最小转弯半径
  279. double correct_angular=solve_angular;
  280. if( (solve_velocity*solve_velocity)/(solve_angular*solve_angular+1e-9) < (radius*radius)) {
  281. correct_angular = fabs(line_velocity) / radius;
  282. if (solve_angular < 0) correct_angular = -correct_angular;
  283. }
  284. ///-----
  285. printf("input : %.4f %.5f(%.5f) output : %.4f %.5f(%.5f) ref : %.3f relative:(%f,%f) time:%.3f\n",
  286. line_velocity,wmg,angular,solve_velocity,solve_angular,correct_angular,
  287. ref_velocity,targetPoseInAGV.x(),targetPoseInAGV.y(),time);
  288. if(solve_velocity>=0 && solve_velocity<min_velocity_)
  289. solve_velocity=min_velocity_;
  290. if(solve_velocity<0 && solve_velocity>-min_velocity_)
  291. solve_velocity=-min_velocity_;
  292. out.push_back(solve_velocity);
  293. out.push_back(correct_angular);
  294. //计算预测轨迹
  295. optimize_trajectory.clear();
  296. for (int i = 0; i < N; ++i)
  297. {
  298. Pose2d pose(solution.x[nx + i], solution.x[ny + i], solution.x[nth + i]);
  299. optimize_trajectory.push_point(pose_agv+pose.rotate(pose_agv.theta()));
  300. }
  301. return true;
  302. }
  303. bool LoadedMPC::filte_Path(const Pose2d& point,const Pose2d& target,const Trajectory& trajectory,
  304. std::vector<Pose2d>& poses,int point_num)
  305. {
  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() < point_num)
  313. return false;
  314. poses.clear();
  315. for (int i = 0; i < trajectory.size(); i++)
  316. {
  317. // 平移加反向旋转到小车坐标系
  318. Pose2d offset=trajectory[i]-point;
  319. double x = offset.x();
  320. double y = offset.y();
  321. double trans_x = x * cos(-theta) - y * sin(-theta);
  322. double trans_y = x * sin(-theta) + y * cos(-theta);
  323. if (trans_x>=0 && poses.size() < point_num)
  324. {
  325. // 旋转到原坐标系
  326. float nx=trans_x * cos(theta) - trans_y * sin(theta);
  327. float ny=trans_x*sin(theta)+trans_y*cos(theta);
  328. Pose2d pose(nx+point.x(),ny+point.y(),trajectory[i].theta());
  329. poses.push_back(pose);
  330. }
  331. }
  332. return true;
  333. }
  334. Eigen::VectorXd LoadedMPC::fit_path(const std::vector<Pose2d>& trajectory)
  335. {
  336. int order=3;
  337. assert(order >= 1 && order <= trajectory.size() - 1);
  338. Eigen::MatrixXd A(trajectory.size(), order + 1);
  339. Eigen::VectorXd yvals(trajectory.size());
  340. for (int i = 0; i < trajectory.size(); i++) {
  341. A(i, 0) = 1.0;
  342. yvals[i]=trajectory[i].y();
  343. }
  344. for (int j = 0; j < trajectory.size(); j++) {
  345. for (int i = 0; i < order; i++) {
  346. A(j, i + 1) = A(j, i) * trajectory[j].x();
  347. }
  348. }
  349. auto Q = A.householderQr();
  350. auto result = Q.solve(yvals);
  351. return result;
  352. }