loaded_mpc.cpp 14 KB

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