frenet_planner.cpp 26 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644
  1. #include "frenet_planner.h"
  2. #include <adc_tools/transfer.h>
  3. #include <common/car_status.h>
  4. #include <adc_tools/parameter_status.h>
  5. //#include <decide_gps_00.h>
  6. #include <adc_planner/lane_change_planner.h>
  7. #include<Eigen/Dense>
  8. using namespace std;
  9. using namespace Eigen;
  10. iv::decition::FrenetPlanner::FrenetPlanner(){
  11. this->planner_id = 1;
  12. this->planner_name = "Frenet";
  13. this->lidarGridPtr = NULL;
  14. }
  15. iv::decition::FrenetPlanner::~FrenetPlanner(){
  16. free(this->lidarGridPtr);
  17. }
  18. /**
  19. * @brief iv::decition::FrenetPlanner::getPath
  20. * 采用的基于frenet坐标系的最优局部路径生成方法,可实现从当前车道变换到另一车道之间的路径生成。还可实现车辆在路线旁起步的“有迹可循”。
  21. * 计算的是,在车辆到达 原始地图路径偏移offset距离的车道 之前,frenet下规划的路径。
  22. *
  23. * @param now_gps_ins 实时gps信息
  24. * @param gpsMapLine 地图数据点
  25. * @param PathPoint 地图路线中距离车辆位置最近的一个点的序号
  26. * @param offset 在车辆避障中,地图源路线所在车道 与 即将去往的车道 之间的距离差值。可以为负值。offset = -(roadNow - roadOri)*roadWidth
  27. * @param lidarGridPtr 激光雷达信息网格
  28. * @return 返回一条车辆坐标系下的路径
  29. */
  30. std::vector<iv::Point2D> iv::decition::FrenetPlanner::getPath(GPS_INS now_gps_ins, const std::vector<GPSData>& gpsMapLine, int PathPoint, double offset, iv::LidarGridPtr lidarGridPtr){
  31. this->roadNow = -1;
  32. this->now_gps_ins = now_gps_ins;
  33. this->gpsMapLine = gpsMapLine;
  34. this->PathPoint = PathPoint;
  35. this->lidarGridPtr = lidarGridPtr;
  36. LaneChangePlanner *lcp = new LaneChangePlanner();
  37. std::vector<iv::Point2D> gpsTrace = lcp->getPath(now_gps_ins,gpsMapLine,PathPoint,0,lidarGridPtr);
  38. delete lcp;
  39. double realSecSpeed = now_gps_ins.speed / 3.6;
  40. leftWidth = offset;
  41. rightWidth = offset;
  42. std::vector<iv::Point2D> trace = getGpsTrace_AfterCalcFrenetTrace(gpsTrace,realSecSpeed);
  43. return trace;
  44. }
  45. /**
  46. * @brief iv::decition::FrenetPlanner::chooseRoadByFrenet
  47. * 用frenet的方法对每条道路考察,选择一个最优的道路
  48. * @param now_gps_ins 实时gps信息
  49. * @param gpsMapLine 地图数据点
  50. * @param PathPoint 地图路线中距离车辆位置最近的一个点的序号
  51. * @param offsetL 在选择道路中,地图源路线左边的最大宽度。可以为负值。offsetL = -(roadSum - 1)*roadWidth
  52. * @param offsetR 在选择道路中,地图源路线右边的最大宽度。可以为非负值。offsetR = (roadOri - 0)*roadWidth
  53. * @param lidarGridPtr 激光雷达信息网格
  54. * @return
  55. */
  56. int iv::decition::FrenetPlanner::chooseRoadByFrenet(GPS_INS now_gps_ins, const std::vector<GPSData>& gpsMapLine, int PathPoint, double offsetL, double offsetR, iv::LidarGridPtr lidarGridPtr,int roadNow){
  57. this->roadNow = roadNow;
  58. this->aimRoadByFrenet = -1;
  59. this->now_gps_ins = now_gps_ins;
  60. this->gpsMapLine = gpsMapLine;
  61. this->PathPoint = PathPoint;
  62. this->lidarGridPtr = lidarGridPtr;
  63. LaneChangePlanner *lcp = new LaneChangePlanner();
  64. std::vector<iv::Point2D> gpsTrace = lcp->getPath(now_gps_ins,gpsMapLine,PathPoint,0,lidarGridPtr);
  65. delete lcp;
  66. double realSecSpeed = now_gps_ins.speed / 3.6;
  67. leftWidth = offsetL;
  68. rightWidth = offsetR;
  69. std::vector<iv::Point2D> trace = getGpsTrace_AfterCalcFrenetTrace(gpsTrace,realSecSpeed);
  70. return aimRoadByFrenet;
  71. }
  72. /**
  73. * @brief iv::decition::FrenetPlanner::getGpsTrace_AfterCalcFrenetTrace
  74. * 进行frenet规划的总函数,还包括了规划前的一些准备工作,比如frenet坐标系建立、车辆起始状态等。
  75. * @param gpsTrace 地图路线上从PathPoint开始的600个点
  76. * @param realsecSpeed 实时车速 [m/s]
  77. * @return 返回一条frenet规划后并转换到车辆坐标系下的路径
  78. */
  79. std::vector<iv::Point2D> iv::decition::FrenetPlanner::getGpsTrace_AfterCalcFrenetTrace(const std::vector<iv::Point2D>& gpsTrace,double realsecSpeed){
  80. vector<Point2D> trace;
  81. vector<FrenetPoint> frenet_s;
  82. double stp=0.0;
  83. //把gpsTrace里的点全部转为frenet坐标系下的点,存储在frenet_s中。相当于frenet坐标系的S轴。
  84. FrenetPoint tmp={.x=gpsTrace[0].x,.y=gpsTrace[0].y,.s=0.0,.d=0.0};
  85. frenet_s.push_back(tmp);
  86. for(int i=1; i<gpsTrace.size(); ++i){
  87. stp+=iv::decition::GetDistance(gpsTrace[i-1],gpsTrace[i]);
  88. tmp={.x=gpsTrace[i].x,.y=gpsTrace[i].y,.s=stp,.d=0.0};
  89. frenet_s.push_back(tmp);
  90. }
  91. //求出车辆当前位置在frenet坐标系下的坐标
  92. // FrenetPoint car_now_at_frenet = XY2Frenet(0,0,gpsTrace);
  93. FrenetPoint car_now_at_frenet = getFrenetfromXY(0,0,gpsTrace,this->gpsMapLine,this->PathPoint,this->now_gps_ins);
  94. double c_s_speed = realsecSpeed * cos(car_now_at_frenet.tangent_Ang-M_PI/2);
  95. double c_d_speed = realsecSpeed * sin(car_now_at_frenet.tangent_Ang-M_PI/2);
  96. double realAcc = ServiceCarStatus.mfCalAcc;
  97. double c_s_dd = realAcc * cos(car_now_at_frenet.tangent_Ang-M_PI/2);
  98. double c_d_dd = realAcc * sin(car_now_at_frenet.tangent_Ang-M_PI/2);
  99. vector<Point2D> path=frenet_optimal_planning(car_now_at_frenet,frenet_s,c_s_speed,c_d_speed,c_d_dd);
  100. return path;
  101. }
  102. /**
  103. * @brief iv::decition::FrenetPlanner::frenet_optimal_planning
  104. * 对frenet规划出的路径进行后续操作,并选出损失最小的一条路径作为最优路径
  105. * @param car_now_frenet_point 车辆当前位置在frenet坐标系下的坐标
  106. * @param frenet_s frenet坐标系的s轴
  107. * @param c_speed 车辆的纵向速度。沿s轴方向的速度。
  108. * @param c_d_d 车辆沿d方向的速度。
  109. * @param c_d_dd 车辆沿d方向的加速度。
  110. * @return 返回一条frenet规划的最优路径
  111. */
  112. vector<iv::Point2D> iv::decition::FrenetPlanner::frenet_optimal_planning(iv::decition::FrenetPoint car_now_frenet_point,
  113. const std::vector<FrenetPoint>& frenet_s, double c_speed, double c_d_d, double c_d_dd){
  114. double s0 = car_now_frenet_point.s;
  115. double c_d = car_now_frenet_point.d;
  116. vector<iv::Point2D> gpsTrace;
  117. vector<Frenet_path> fplist=calc_frenet_paths(c_speed, c_d, c_d_d, c_d_dd, s0); //frenet规划
  118. sort(fplist.begin(),fplist.end(),comp); //按损失度由小到大进行排序
  119. for(int i=0; i<fplist.size(); ++i){
  120. calc_global_single_path(fplist[i],frenet_s);
  121. if(check_single_path(fplist[i])){
  122. gpsTrace = frenet_path_to_gpsTrace(fplist[i]);
  123. aimRoadByFrenet = fplist[i].roadflag;
  124. return gpsTrace;
  125. }
  126. }
  127. return gpsTrace;
  128. /*
  129. // calc_global_paths(fplist, frenet_s); //生成frenet路径中每个点在车辆坐标系下的坐标
  130. // fplist = check_paths(fplist); //检验计算出的每条路径
  131. // //找到损失最小的轨迹
  132. // double min_cost = (numeric_limits<double>::max)();
  133. // Frenet_path bestpath;
  134. // for(int i=0; i<fplist.size(); ++i){
  135. // if(min_cost > fplist[i].cf){
  136. // min_cost = fplist[i].cf;
  137. // bestpath = fplist[i];
  138. // }
  139. // }
  140. // gpsTrace = frenet_path_to_gpsTrace(bestpath);
  141. // aimRoadByFrenet = bestpath.roadflag;
  142. // return gpsTrace;
  143. */
  144. }
  145. /**
  146. * @brief iv::decition::FrenetPlanner::calc_frenet_paths
  147. * 正式规划出不同的frenet路径,并统计相应的损失度。单从车辆行驶的平滑性计算而得,后续需检测是否有障碍物。
  148. * @param c_speed 车辆的纵向速度。沿s轴方向的速度
  149. * @param c_d 车辆的横向(d方向)偏移距离
  150. * @param c_d_d 车辆沿d方向的速度
  151. * @param c_d_dd 车辆沿d方向的加速度
  152. * @param s0 车辆沿s方向的坐标
  153. * @return 返回多条frenet路径
  154. */
  155. vector<iv::decition::Frenet_path> iv::decition::FrenetPlanner::calc_frenet_paths(double c_speed, double c_d, double c_d_d, double c_d_dd, double s0){
  156. vector<iv::decition::Frenet_path> frenet_paths;
  157. int roadNum = round(abs((leftWidth-rightWidth)/ServiceParameterStatus.D_ROAD_W)); //roadNum为frenet算法的起始道路序号
  158. //采样,并对每一个目标配置生成轨迹
  159. for(double di=leftWidth; di<=rightWidth; di+=ServiceParameterStatus.D_ROAD_W,roadNum--){
  160. if(roadNum == this->roadNow)
  161. continue;
  162. //横向动作规划
  163. for(double Ti=ServiceParameterStatus.MINT; Ti<ServiceParameterStatus.MAXT; Ti+=ServiceParameterStatus.DT){
  164. Frenet_path fp;
  165. fp.roadflag = roadNum;
  166. //计算出关于目标配置di,Ti的横向多项式
  167. Quintic_polynomial lat_qp = Quintic_polynomial(c_d, c_d_d, c_d_dd, di, 0.0, 0.0, Ti);
  168. for(double i=0; i<Ti; i+=ServiceParameterStatus.D_POINT_T)
  169. fp.t.push_back(i);
  170. for(int i=0; i<fp.t.size(); ++i){
  171. fp.d.push_back(lat_qp.calc_point(fp.t[i]));
  172. fp.d_d.push_back(lat_qp.calc_first_derivative(fp.t[i]));
  173. fp.d_dd.push_back(lat_qp.calc_second_derivative(fp.t[i]));
  174. fp.d_ddd.push_back(lat_qp.calc_third_derivative(fp.t[i]));
  175. }
  176. //纵向速度规划 (速度保持)
  177. for(double tv=ServiceParameterStatus.TARGET_SPEED - ServiceParameterStatus.D_T_S * ServiceParameterStatus.N_S_SAMPLE;
  178. tv<(ServiceParameterStatus.TARGET_SPEED + ServiceParameterStatus.D_T_S * ServiceParameterStatus.N_S_SAMPLE);
  179. tv+=ServiceParameterStatus.D_T_S){
  180. Frenet_path tfp = fp;
  181. Quartic_polynomial lon_qp = Quartic_polynomial(s0, c_speed, 0.0, tv, 0.0, Ti);
  182. for(int i=0; i<fp.t.size(); ++i){
  183. tfp.s.push_back(lon_qp.calc_point(fp.t[i]));
  184. tfp.s_d.push_back(lon_qp.calc_first_derivative(fp.t[i]));
  185. tfp.s_dd.push_back(lon_qp.calc_second_derivative(fp.t[i]));
  186. tfp.s_ddd.push_back(lon_qp.calc_third_derivative(fp.t[i]));
  187. }
  188. //square of jerk
  189. double Jp = inner_product(tfp.d_ddd.begin(), tfp.d_ddd.end(), tfp.d_ddd.begin(), 0);
  190. //square of jerk
  191. double Js = inner_product(tfp.s_ddd.begin(), tfp.s_ddd.end(), tfp.s_ddd.begin(), 0);
  192. //square of diff from target speed
  193. double ds = pow((ServiceParameterStatus.TARGET_SPEED - tfp.s_d.back()),2);
  194. //横向的损失函数
  195. tfp.cd = ServiceParameterStatus.KJ * Jp + ServiceParameterStatus.KT * Ti + ServiceParameterStatus.KD * tfp.d.back() * tfp.d.back();
  196. //纵向的损失函数
  197. tfp.cv = ServiceParameterStatus.KJ * Js + ServiceParameterStatus.KT * Ti + ServiceParameterStatus.KD * ds;
  198. //总的损失函数为d 和 s方向的损失函数乘对应的系数相加
  199. tfp.cf = ServiceParameterStatus.KLAT * tfp.cd + ServiceParameterStatus.KLON * tfp.cv;
  200. frenet_paths.push_back(tfp);
  201. }
  202. }
  203. }
  204. return frenet_paths;
  205. }
  206. /**
  207. * @brief iv::decition::FrenetPlanner::calc_global_paths
  208. * 计算出每条frenet路径中轨迹点的x,y坐标。x,y坐标是轨迹点在车辆坐标系下的横纵坐标。
  209. * 部分函数参数在第一种计算XY坐标的方法中没有使用,但在第二种方法中会用到。
  210. * @param fplist 多条frenet路径
  211. * @param frenet_s frenet坐标系的s轴
  212. * @return 通过引用传递返回带有x,y值的多条frenet路径
  213. */
  214. void iv::decition::FrenetPlanner::calc_global_paths(vector<Frenet_path>& fplist,const std::vector<FrenetPoint>& frenet_s){
  215. for(auto& fp:fplist){
  216. for(int i=0; i<fp.s.size(); ++i){
  217. double ix,iy;
  218. // Frenet2XY(&ix,&iy,fp.s[i],fp.d[i],frenet_s); //第一种方法
  219. getXYfromFrenet(&ix,&iy,fp.s[i],fp.d[i],frenet_s,this->gpsMapLine,this->PathPoint,this->now_gps_ins); //第二种方法
  220. fp.x.push_back(ix);
  221. fp.y.push_back(iy);
  222. }
  223. for(int i=0; i<(fp.x.size()-1); ++i){
  224. double dx = fp.x[i+1] - fp.x[i];
  225. double dy = fp.y[i+1] - fp.y[i];
  226. fp.yaw.push_back(atan2(dy,dx));
  227. fp.ds.push_back(sqrt(dx*dx + dy*dy));
  228. }
  229. fp.ds.push_back(fp.ds.back());
  230. fp.yaw.push_back(fp.yaw.back());
  231. for(int i = 0; i < (fp.yaw.size() - 1); ++i){
  232. fp.c.push_back((fp.yaw[i + 1] - fp.yaw[i]) / fp.ds[i]);
  233. }
  234. }
  235. }
  236. void iv::decition::FrenetPlanner::calc_global_single_path(Frenet_path &fp, const std::vector<FrenetPoint> &frenet_s){
  237. for(int i=0; i<fp.s.size(); ++i){
  238. double ix,iy;
  239. // Frenet2XY(&ix,&iy,fp.s[i],fp.d[i],frenet_s); //第一种方法
  240. getXYfromFrenet(&ix,&iy,fp.s[i],fp.d[i],frenet_s,this->gpsMapLine,this->PathPoint,this->now_gps_ins); //第二种方法
  241. fp.x.push_back(ix);
  242. fp.y.push_back(iy);
  243. }
  244. for(int i=0; i<(fp.x.size()-1); ++i){
  245. double dx = fp.x[i+1] - fp.x[i];
  246. double dy = fp.y[i+1] - fp.y[i];
  247. fp.yaw.push_back(atan2(dy,dx));
  248. fp.ds.push_back(sqrt(dx*dx + dy*dy));
  249. }
  250. fp.ds.push_back(fp.ds.back());
  251. fp.yaw.push_back(fp.yaw.back());
  252. for(int i = 0; i < (fp.yaw.size() - 1); ++i){
  253. fp.c.push_back((fp.yaw[i + 1] - fp.yaw[i]) / fp.ds[i]);
  254. }
  255. }
  256. /**
  257. * @brief iv::decition::FrenetPlanner::check_paths
  258. * 对多条frenet路径进行检验,排除不符合要求的路径。
  259. * @param fplist 多条frenet路径
  260. * @return 排除部分路径后的多条frenet路径
  261. */
  262. vector<iv::decition::Frenet_path> iv::decition::FrenetPlanner::check_paths(const vector<Frenet_path>& fplist){
  263. vector<Frenet_path> okind;
  264. int i=0;
  265. int j=0;
  266. for(i=0; i<fplist.size(); ++i){
  267. cout<<"&&&&&&&&&&fplist[i].roadflag: "<<fplist[i].roadflag<<endl;
  268. for(j=0; j<fplist[i].s_d.size(); ++j){
  269. if(fplist[i].s_d[j]>ServiceParameterStatus.MAX_SPEED) //最大速度检查
  270. goto ContinueFlag;
  271. }
  272. for(j=0; j<fplist[i].s_dd.size(); ++j){
  273. if(abs(fplist[i].s_dd[j])>ServiceParameterStatus.MAX_ACCEL) //最大加速度检查
  274. goto ContinueFlag;
  275. }
  276. for(j=30; j<fplist[i].c.size()-30; ++j){
  277. if(abs(fplist[i].c[j])>ServiceParameterStatus.MAX_CURVATURE)//最大曲率检查
  278. goto ContinueFlag;
  279. }
  280. if(!check_collision(fplist[i]))
  281. continue;
  282. okind.push_back(fplist[i]);
  283. ContinueFlag:continue;
  284. }
  285. return okind;
  286. }
  287. bool iv::decition::FrenetPlanner::check_single_path(const iv::decition::Frenet_path &fp){
  288. int j=0;
  289. cout<<"&&&&&&&&&&fp.roadflag: "<<fp.roadflag<<endl;
  290. for(j=0; j<fp.s_d.size(); ++j){
  291. if(fp.s_d[j]>ServiceParameterStatus.MAX_SPEED) //最大速度检查
  292. return false;
  293. }
  294. for(j=0; j<fp.s_dd.size(); ++j){
  295. if(abs(fp.s_dd[j])>ServiceParameterStatus.MAX_ACCEL) //最大加速度检查
  296. return false;
  297. }
  298. for(j=30; j<fp.c.size()-30; ++j){
  299. if(abs(fp.c[j])>ServiceParameterStatus.MAX_CURVATURE)//最大曲率检查
  300. return false;
  301. }
  302. if(!check_collision(fp))
  303. return false;
  304. return true;
  305. }
  306. /**
  307. * @brief iv::decition::FrenetPlanner::check_collision
  308. * 检验frenet路径上是否有障碍物,调用的是改进的函数computeObsOnRoadByFrenet。
  309. * @param frenet_path 一条frenet路径
  310. * @param car_now_frenet_point 车辆当前位置在frenet坐标系下的坐标
  311. * @return 在路径上有障碍物返回false,否则返回true。
  312. */
  313. bool iv::decition::FrenetPlanner::check_collision(const iv::decition::Frenet_path &frenet_path){
  314. std::vector<Point2D> gpsTrace = frenet_path_to_gpsTrace(frenet_path);
  315. double obs=-1;
  316. // iv::decition::DecideGps00().computeObsOnRoadByFrenet(this->lidarGridPtr,gpsTrace,obs,this->gpsMapLine,this->PathPoint,this->now_gps_ins);
  317. if(obs > 0 && obs < 30)
  318. return false;
  319. else
  320. return true;
  321. }
  322. /**
  323. * @brief iv::decition::FrenetPlanner::frenet_path_to_gpsTrace
  324. * 将frenet路径转换到车辆坐标系下。
  325. * @param frenet_path 一条frenet路径
  326. * @return 一条车辆坐标系下的路径
  327. */
  328. vector<iv::Point2D> iv::decition::FrenetPlanner::frenet_path_to_gpsTrace(const Frenet_path& frenet_path){
  329. vector<iv::Point2D> gpsTrace;
  330. for (int i=0; i<frenet_path.x.size(); ++i) {
  331. gpsTrace.push_back(Point2D(frenet_path.x[i],frenet_path.y[i]));
  332. gpsTrace[i].speed = sqrt(frenet_path.d_d[i]*frenet_path.d_d[i]+frenet_path.s_d[i]*frenet_path.s_d[i])*3.6;
  333. }
  334. return gpsTrace;
  335. }
  336. double iv::decition::FrenetPlanner::distance(double x1, double y1, double x2, double y2)
  337. {
  338. return sqrt((x2-x1)*(x2-x1)+(y2-y1)*(y2-y1));
  339. }
  340. //找出gpsTrace中距离(x,y)最近的一个点
  341. int iv::decition::FrenetPlanner::ClosestWaypoint(double x, double y, const std::vector<Point2D>& gpsTrace)
  342. {
  343. double closestLen = 100000; //large number
  344. int closestWaypoint = 0;
  345. for(int i = 1; i < gpsTrace.size(); i++)
  346. {
  347. double map_x = gpsTrace[i].x;
  348. double map_y = gpsTrace[i].y;
  349. double dist = distance(x,y,map_x,map_y);
  350. if(dist < closestLen)
  351. {
  352. closestLen = dist;
  353. closestWaypoint = i;
  354. }
  355. }
  356. return closestWaypoint;
  357. }
  358. /* |==========================================================|
  359. * | 车辆坐标系与 frenet 坐标系互转的第一种方法。 |
  360. * |==========================================================| */
  361. // 车体坐标转frenet坐标。frenet坐标原点是 gpsTrace 中序号为0的点。
  362. // Transform from Cartesian x,y coordinates to Frenet s,d coordinates
  363. iv::decition::FrenetPoint iv::decition::FrenetPlanner::XY2Frenet(double x, double y, const std::vector<iv::Point2D>& gpsTrace){
  364. int next_wp=ClosestWaypoint( x, y, gpsTrace);
  365. int prev_wp = next_wp-1; //prev_wp代表在next_wp的前一个点计算坐标,能够保证frenet_s都是依次相加的。避免在next_wp计算frenet_s的话,可能出现减的情况。
  366. // if(next_wp == 0){
  367. // prev_wp = gpsTrace.size()-1;
  368. // }
  369. double n_x = gpsTrace[next_wp].x-gpsTrace[prev_wp].x;
  370. double n_y = gpsTrace[next_wp].y-gpsTrace[prev_wp].y;
  371. double x_x = x - gpsTrace[prev_wp].x;
  372. double x_y = y - gpsTrace[prev_wp].y;
  373. // find the projection of x onto n
  374. double proj_norm = (x_x*n_x+x_y*n_y)/(n_x*n_x+n_y*n_y);
  375. double proj_x = proj_norm*n_x;
  376. double proj_y = proj_norm*n_y; //proj_x、proj_y应该为垂足的坐标
  377. double frenet_d = sqrt((x_x - proj_x) * (x_x - proj_x) + (x_y - proj_y) * (x_y - proj_y));
  378. //经手动推算frenet_d = abs(n_x * x_y - n_y * x_x) / sqrt(n_x * n_x + n_y * n_y)。
  379. //即frenet_d,等于点(x,y)到 过prev_wp、next_wp两点的直线 的垂直距离。
  380. //see if d value is positive or negative by comparing it to a center point
  381. double center_x = 1000-gpsTrace[prev_wp].x;
  382. double center_y = 2000-gpsTrace[prev_wp].y;
  383. double centerToPos = distance(center_x,center_y,x_x,x_y);
  384. double centerToRef = distance(center_x,center_y,proj_x,proj_y);
  385. if(centerToPos <= centerToRef){
  386. frenet_d *= -1;
  387. }
  388. // calculate s value
  389. double frenet_s = 0;
  390. for(int i = 0; i < prev_wp; i++){
  391. frenet_s += distance(gpsTrace[i].x,gpsTrace[i].y,gpsTrace[i+1].x,gpsTrace[i+1].y);
  392. }
  393. if(prev_wp<=0){
  394. frenet_s -= distance(0,0,proj_x,proj_y);
  395. }else{
  396. frenet_s += distance(0,0,proj_x,proj_y);
  397. }
  398. double tmp_Angle = atan2(n_y,n_x);
  399. return {x:x,y:y,s:frenet_s,d:frenet_d,tangent_Ang:tmp_Angle};
  400. }
  401. // frenet坐标转车体坐标。
  402. // Transform from Frenet s,d coordinates to Cartesian x,y
  403. void iv::decition::FrenetPlanner::Frenet2XY(double *res_x, double *res_y, double s, double d, const vector<iv::decition::FrenetPoint>& frenetTrace){
  404. int prev_wp = 0;
  405. //退出循环时,prev_wp 最大是等于 frenetTrace.size()-2。
  406. while(s > frenetTrace[prev_wp+1].s && (prev_wp < (int)(frenetTrace.size()-2) )){
  407. prev_wp++;
  408. }
  409. int wp2 = prev_wp+1;
  410. double heading = atan2((frenetTrace[wp2].y-frenetTrace[prev_wp].y),(frenetTrace[wp2].x-frenetTrace[prev_wp].x));
  411. double seg_s = (s-frenetTrace[prev_wp].s);
  412. double seg_x = frenetTrace[prev_wp].x+seg_s*cos(heading);
  413. double seg_y = frenetTrace[prev_wp].y+seg_s*sin(heading);
  414. double perp_heading = heading-M_PI*0.5;
  415. *res_x = seg_x + d*cos(perp_heading);
  416. *res_y = seg_y + d*sin(perp_heading);
  417. }
  418. /* |==========================================================|
  419. * | 车辆坐标系与 frenet 坐标系互转的第二种方法。 |
  420. * |==========================================================| */
  421. // 车体坐标转frenet坐标。frenet坐标原点是 gpsTrace 中序号为0的点。
  422. iv::decition::FrenetPoint iv::decition::FrenetPlanner::getFrenetfromXY(double x, double y, const std::vector<iv::Point2D>& gpsTrace,const std::vector<iv::GPSData>& gpsMap,int pathpoint,GPS_INS nowGps){
  423. int next_wp=ClosestWaypoint( x, y, gpsTrace);
  424. int prev_wp = next_wp-1; //prev_wp代表在next_wp的前一个点计算坐标,能够保证frenet_s都是依次相加的。避免在next_wp计算frenet_s的话,可能出现减的情况。
  425. // if(next_wp == 0){
  426. // prev_wp = gpsTrace.size()-1;
  427. // }
  428. GPS_INS gps = Coordinate_UnTransfer(x,y,nowGps);
  429. Point2D pt = Coordinate_Transfer(gps.gps_x,gps.gps_y, *gpsMap[(pathpoint+prev_wp)%gpsMap.size()]);
  430. // calculate s value
  431. double frenet_s = 0;
  432. for(int i = 0; i < prev_wp; i++){
  433. frenet_s += distance(gpsTrace[i].x,gpsTrace[i].y,gpsTrace[i+1].x,gpsTrace[i+1].y);
  434. }
  435. frenet_s += pt.y;
  436. //theta为prev_wp处车的航向角 与 nowGps处的车辆坐标系下x轴之间的夹角,逆时针为正。
  437. double theta = (nowGps.ins_heading_angle - gpsMap[(pathpoint+prev_wp)%gpsMap.size()]->ins_heading_angle+90);
  438. double tmp_Angle = theta * M_PI / 180;
  439. return {x:x,y:y,s:frenet_s,d:pt.x,tangent_Ang:tmp_Angle};
  440. }
  441. void iv::decition::FrenetPlanner::getXYfromFrenet(double *res_x, double *res_y, double s, double d, const vector<iv::decition::FrenetPoint>& frenetTrace,const std::vector<iv::GPSData>& gpsMap,int pathpoint,GPS_INS nowGps)
  442. {
  443. int prev_wp = -1;
  444. while((prev_wp < (int)(frenetTrace.size()-1) ) && s > frenetTrace[prev_wp+1].s)
  445. {
  446. prev_wp++;
  447. }
  448. if(prev_wp < 0){
  449. prev_wp = 0;
  450. }
  451. // int wp2 =prev_wp+1;
  452. GPS_INS gps= Coordinate_UnTransfer( d, s-frenetTrace[prev_wp].s , *gpsMap[(pathpoint+prev_wp)%gpsMap.size()]);
  453. Point2D pt = Coordinate_Transfer( gps.gps_x, gps.gps_y, nowGps);
  454. *res_x = pt.x;
  455. *res_y = pt.y;
  456. }
  457. iv::decition::Quintic_polynomial::Quintic_polynomial(double xs, double vxs, double axs, double xe, double vxe, double axe, double T){
  458. //计算五次多项式系数
  459. this->xs = xs;
  460. this->vxs = vxs;
  461. this->axs = axs;
  462. this->xe = xe;
  463. this->vxe = vxe;
  464. this->axe = axe;
  465. this->a0 = xs;
  466. this->a1 = vxs;
  467. this->a2 = axs/ 2.0;
  468. MatrixXd A(3, 3);
  469. MatrixXd b(3, 1);
  470. MatrixXd x(3, 1);
  471. A << pow(T, 3), pow(T, 4), pow(T, 5),
  472. 3*pow(T, 2), 4*pow(T, 3), 5*pow(T, 4),
  473. 6*T, 12*T*T, 20*pow(T, 3);
  474. b << xe - a0 - a1*T - a2*T*T,
  475. vxe - a1 - 2*a2*T,
  476. axe - 2*a2;
  477. x=A.colPivHouseholderQr().solve(b);
  478. this->a3 = x(0,0);
  479. this->a4 = x(1,0);
  480. this->a5 = x(2,0);
  481. }
  482. iv::decition::Quintic_polynomial::~Quintic_polynomial(){
  483. }
  484. double iv::decition::Quintic_polynomial::calc_point(double t){
  485. double xt = this->a0 + this->a1 * t + this->a2 * t*t + this->a3 * t*t*t + this->a4 * t*t*t*t + this->a5 * t*t*t*t*t;
  486. return xt;
  487. }
  488. double iv::decition::Quintic_polynomial::calc_first_derivative(double t){
  489. double xt = this->a1 + 2*this->a2 * t + 3*this->a3 * t*t + 4*this->a4 * t*t*t + 5*this->a5 * t*t*t*t;
  490. return xt;
  491. }
  492. double iv::decition::Quintic_polynomial::calc_second_derivative(double t){
  493. double xt = 2*this->a2 + 6*this->a3 * t + 12*this->a4 * t*t + 20*this->a5 * t*t*t;
  494. return xt;
  495. }
  496. double iv::decition::Quintic_polynomial::calc_third_derivative(double t){
  497. double xt = 6*this->a3 + 24*this->a4 * t + 60*this->a5 * t*t;
  498. return xt;
  499. }
  500. iv::decition::Quartic_polynomial::Quartic_polynomial(double xs, double vxs, double axs, double vxe, double axe, double T){
  501. //计算四次多项式系数
  502. this->xs = xs;
  503. this->vxs = vxs;
  504. this->axs = axs;
  505. this->vxe = vxe;
  506. this->axe = axe;
  507. this->a0 = xs;
  508. this->a1 = vxs;
  509. this->a2 = axs / 2.0;
  510. MatrixXd A(2, 2);
  511. MatrixXd b(2, 1);
  512. MatrixXd x(2, 1);
  513. A << 3*pow(T, 2), 4*pow(T, 3),
  514. 6*T, 12*T*T ;
  515. b << vxe - a1 - 2*a2*T,
  516. axe - 2*a2;
  517. x=A.colPivHouseholderQr().solve(b);
  518. this->a3 = x(0,0);
  519. this->a4 = x(1,0);
  520. }
  521. iv::decition::Quartic_polynomial::~Quartic_polynomial(){
  522. }
  523. double iv::decition::Quartic_polynomial::calc_point(double t){
  524. double xt = this->a0 + this->a1*t + this->a2*t*t + this->a3*t*t*t + this->a4*t*t*t*t;
  525. return xt;
  526. }
  527. double iv::decition::Quartic_polynomial::calc_first_derivative(double t){
  528. double xt = this->a1 + 2*this->a2*t + 3*this->a3*t*t + 4*this->a4*t*t*t;
  529. return xt;
  530. }
  531. double iv::decition::Quartic_polynomial::calc_second_derivative(double t){
  532. double xt = 2*this->a2 + 6*this->a3*t + 12*this->a4*t*t;
  533. return xt;
  534. }
  535. double iv::decition::Quartic_polynomial::calc_third_derivative(double t){
  536. double xt = 6*this->a3 + 24*this->a4*t;
  537. return xt;
  538. }
  539. bool iv::decition::FrenetPlanner::comp(const iv::decition::Frenet_path &a, const iv::decition::Frenet_path &b){
  540. return a.cf < b.cf;
  541. }