loaded_mpc.cpp 14 KB

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