loaded_mpc.cpp 14 KB

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