frenet_planner.h 6.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161
  1. #ifndef FRENET_PLANNER_H
  2. #define FRENET_PLANNER_H
  3. #include "base_planner.h"
  4. namespace iv{
  5. namespace decition{
  6. //x,y分别为frenet轨迹点相对于车辆的x,y轴坐标
  7. //s,d分别为frenet轨迹点相对于frenet坐标系的s,d轴坐标值
  8. //tangent_Ang为轨迹点在frenet坐标系的s轴的投影处的 切线 与车辆坐标系x轴之间的夹角。
  9. //tangent_Ang用于分解计算车辆分别在s轴、d轴方向上的运动速度、加速度等。
  10. struct FrenetPoint{
  11. double x;
  12. double y;
  13. double s;
  14. double d;
  15. double tangent_Ang;
  16. };
  17. class Quintic_polynomial
  18. {
  19. public:
  20. Quintic_polynomial(double xs, double vxs, double axs, double xe, double vxe, double axe, double T);
  21. ~Quintic_polynomial();
  22. private:
  23. // 计算五次多项式系数
  24. double xs; //d0
  25. double vxs; //d.0
  26. double axs; //d..0
  27. double xe; //d1
  28. double vxe; //d.1
  29. double axe; //d..1
  30. double a0;
  31. double a1;
  32. double a2;
  33. double a3;
  34. double a4;
  35. double a5;
  36. public:
  37. double calc_point(double t);
  38. double calc_first_derivative(double t);
  39. double calc_second_derivative(double t);
  40. double calc_third_derivative(double t);
  41. };
  42. class Quartic_polynomial
  43. {
  44. public:
  45. Quartic_polynomial(double xs, double vxs, double axs, double vxe, double axe, double T);
  46. ~Quartic_polynomial();
  47. private:
  48. //计算四次多项式系数
  49. double xs;
  50. double vxs;
  51. double axs;
  52. double vxe;
  53. double axe;
  54. double a0;
  55. double a1;
  56. double a2;
  57. double a3;
  58. double a4;
  59. public:
  60. double calc_point(double t);
  61. double calc_first_derivative(double t);
  62. double calc_second_derivative(double t);
  63. double calc_third_derivative(double t);
  64. };
  65. class Frenet_path
  66. {
  67. public:
  68. std::vector<double> t;
  69. std::vector<double> d;
  70. std::vector<double> d_d;
  71. std::vector<double> d_dd;
  72. std::vector<double> d_ddd;
  73. std::vector<double> s;
  74. std::vector<double> s_d;
  75. std::vector<double> s_dd;
  76. std::vector<double> s_ddd;
  77. int roadflag = -1; //标记每一条frenet路径,是以哪一条道路为目标道路的
  78. double cd = 0.0;
  79. double cv = 0.0;
  80. double cf = 0.0;
  81. std::vector<double> x;
  82. std::vector<double> y;
  83. std::vector<double> yaw;
  84. std::vector<double> ds;
  85. std::vector<double> c;
  86. };
  87. class FrenetPlanner : public BasePlanner{
  88. public:
  89. int aimRoadByFrenet = -1; //记录由frenet规划选择出来的道路序号
  90. int roadNow = -1; //记录避障时车辆当前道路序号,规划路径时,避开此条道路
  91. double leftWidth = 0.0; //中心线左边偏移距离,为负值
  92. double rightWidth = 0.0; //中心线右边偏移距离,为正值
  93. GPS_INS now_gps_ins; //实时gps信息
  94. std::vector<GPSData> gpsMapLine; //地图数据点
  95. int PathPoint = 0; //地图路线中距离车辆位置最近的一个点的序号
  96. iv::LidarGridPtr lidarGridPtr; //激光雷达信息网格
  97. public:
  98. FrenetPlanner();
  99. ~FrenetPlanner();
  100. /**
  101. * @brief iv::decition::FrenetPlanner::getPath
  102. * 采用的基于frenet坐标系的最优局部路径生成方法,可实现从当前车道变换到另一车道之间的路径生成。还可实现车辆在路线旁起步的“有迹可循”。
  103. * 计算的是,在车辆到达 原始地图路径偏移offset距离的车道 之前,frenet下规划的路径。
  104. *
  105. * @param now_gps_ins 实时gps信息
  106. * @param gpsMapLine 地图数据点
  107. * @param PathPoint 地图路线中距离车辆位置最近的一个点的序号
  108. * @param offset 在车辆避障中,地图源路线所在车道 与 即将去往的车道 之间的距离差值。可以为负值。
  109. * @param lidarGridPtr 激光雷达信息网格
  110. * @return 返回一条车辆坐标系下的路径
  111. */
  112. std::vector<iv::Point2D> getPath(GPS_INS now_gps_ins, const std::vector<GPSData>& gpsMapLine, int PathPoint, double offset, iv::LidarGridPtr lidarGridPtr);
  113. int chooseRoadByFrenet(GPS_INS now_gps_ins, const std::vector<GPSData>& gpsMapLine, int PathPoint, double offsetL, double offsetR, iv::LidarGridPtr lidarGridPtr,int roadNow);
  114. static iv::decition::FrenetPoint XY2Frenet(double x, double y, const std::vector<Point2D>& gpsTracet);
  115. static void Frenet2XY(double *x, double *y, double s, double d, const std::vector<iv::decition::FrenetPoint>& frenetTrace);
  116. static double distance(double x1, double y1, double x2, double y2);
  117. static int ClosestWaypoint(double x, double y, const std::vector<Point2D>& gpsTrace);
  118. static FrenetPoint getFrenetfromXY(double x, double y, const std::vector<iv::Point2D>& gpsTrace,const std::vector<iv::GPSData>& gpsMap,int pathpoint,GPS_INS nowGps);
  119. static void getXYfromFrenet(double *res_x, double *res_y, double s, double d, const std::vector<iv::decition::FrenetPoint>& frenetTrace,const std::vector<iv::GPSData>& gpsMap,int pathpoint,GPS_INS nowGps);
  120. static bool comp(const iv::decition::Frenet_path &a,const iv::decition::Frenet_path &b);
  121. private:
  122. std::vector<iv::Point2D> getGpsTrace_AfterCalcFrenetTrace(const std::vector<iv::Point2D>& gpsTrace,double realsecSpeed);
  123. std::vector<iv::Point2D> frenet_optimal_planning(FrenetPoint car_now_frenet_point,
  124. const std::vector<FrenetPoint>& frenet_s,
  125. double c_speed, double c_d_d, double c_d_dd);
  126. std::vector<Frenet_path> calc_frenet_paths(double c_speed, double c_d, double c_d_d, double c_d_dd, double s0);
  127. void calc_global_paths(std::vector<Frenet_path>& fplist,const std::vector<FrenetPoint>& frenet_s);
  128. void calc_global_single_path(Frenet_path& fp,const std::vector<FrenetPoint>& frenet_s);
  129. std::vector<Frenet_path> check_paths(const std::vector<Frenet_path>& fplist);
  130. bool check_single_path(const Frenet_path &fp);
  131. bool check_collision(const Frenet_path &frenet_path);
  132. std::vector<Point2D> frenet_path_to_gpsTrace(const Frenet_path& frenet_path);
  133. };
  134. }
  135. }
  136. #endif // FRENET_PLANNER_H