PlannerH.cpp 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495
  1. /// \file PlannerH.cpp
  2. /// \brief Main functions for path generation (global and local)
  3. /// \author Hatem Darweesh
  4. /// \date Dec 14, 2016
  5. #include "op_planner/PlannerH.h"
  6. #include "op_planner/PlanningHelpers.h"
  7. #include "op_planner/MappingHelpers.h"
  8. #include <iostream>
  9. using namespace std;
  10. using namespace UtilityHNS;
  11. namespace PlannerHNS
  12. {
  13. PlannerH::PlannerH()
  14. {
  15. //m_Params = params;
  16. }
  17. PlannerH::~PlannerH()
  18. {
  19. }
  20. void PlannerH::GenerateRunoffTrajectory(const std::vector<std::vector<WayPoint> >& referencePaths,const WayPoint& carPos, const bool& bEnableLaneChange, const double& speed, const double& microPlanDistance,
  21. const double& maxSpeed,const double& minSpeed, const double& carTipMargin, const double& rollInMargin,
  22. const double& rollInSpeedFactor, const double& pathDensity, const double& rollOutDensity,
  23. const int& rollOutNumber, const double& SmoothDataWeight, const double& SmoothWeight,
  24. const double& SmoothTolerance, const double& speedProfileFactor, const bool& bHeadingSmooth,
  25. const int& iCurrGlobalPath, const int& iCurrLocalTraj,
  26. std::vector<std::vector<std::vector<WayPoint> > >& rollOutsPaths,
  27. std::vector<WayPoint>& sampledPoints_debug)
  28. {
  29. if(referencePaths.size()==0) return;
  30. if(microPlanDistance <=0 ) return;
  31. rollOutsPaths.clear();
  32. sampledPoints_debug.clear(); //for visualization only
  33. for(unsigned int i = 0; i < referencePaths.size(); i++)
  34. {
  35. std::vector<std::vector<WayPoint> > local_rollOutPaths;
  36. int s_index = 0, e_index = 0;
  37. vector<double> e_distances;
  38. if(referencePaths.at(i).size()>0)
  39. {
  40. PlanningHelpers::CalculateRollInTrajectories(carPos, speed, referencePaths.at(i), s_index, e_index, e_distances,
  41. local_rollOutPaths, microPlanDistance, maxSpeed, carTipMargin, rollInMargin,
  42. rollInSpeedFactor, pathDensity, rollOutDensity,rollOutNumber,
  43. SmoothDataWeight, SmoothWeight, SmoothTolerance, bHeadingSmooth, sampledPoints_debug);
  44. }
  45. else
  46. {
  47. for(int j=0; j< rollOutNumber+1; j++)
  48. {
  49. local_rollOutPaths.push_back(vector<WayPoint>());
  50. }
  51. }
  52. rollOutsPaths.push_back(local_rollOutPaths);
  53. }
  54. }
  55. double PlannerH::PlanUsingDPRandom(const WayPoint& start,
  56. const double& maxPlanningDistance,
  57. RoadNetwork& map,
  58. std::vector<std::vector<WayPoint> >& paths)
  59. {
  60. PlannerHNS::WayPoint* pStart = PlannerHNS::MappingHelpers::GetClosestBackWaypointFromMap(start, map);
  61. if(!pStart)
  62. {
  63. GPSPoint sp = start.pos;
  64. cout << endl << "Error: PlannerH -> Can't Find Global Waypoint Nodes in the Map for Start (" << sp.ToString() << ")" << endl;
  65. return 0;
  66. }
  67. if(!pStart->pLane)
  68. {
  69. cout << endl << "Error: PlannerH -> Null Lane, Start (" << pStart->pLane << ")" << endl;
  70. return 0;
  71. }
  72. RelativeInfo start_info;
  73. PlanningHelpers::GetRelativeInfo(pStart->pLane->points, start, start_info);
  74. if(start_info.perp_distance > START_POINT_MAX_DISTANCE)
  75. {
  76. GPSPoint sp = start.pos;
  77. cout << endl << "Error: PlannerH -> Start Distance to Lane is: " << start_info.perp_distance
  78. << ", Pose: " << sp.ToString() << ", LanePose:" << start_info.perp_point.pos.ToString()
  79. << ", LaneID: " << pStart->pLane->id << " -> Check origin and vector map. " << endl;
  80. return 0;
  81. }
  82. vector<WayPoint*> local_cell_to_delete;
  83. WayPoint* pLaneCell = 0;
  84. pLaneCell = PlanningHelpers::BuildPlanningSearchTreeStraight(pStart, maxPlanningDistance, local_cell_to_delete);
  85. if(!pLaneCell)
  86. {
  87. cout << endl << "PlannerH -> Plan (B) Failed, Sorry we Don't have plan (C) This is the END." << endl;
  88. return 0;
  89. }
  90. vector<WayPoint> path;
  91. vector<vector<WayPoint> > tempCurrentForwardPathss;
  92. const std::vector<int> globalPath;
  93. PlanningHelpers::TraversePathTreeBackwards(pLaneCell, pStart, globalPath, path, tempCurrentForwardPathss);
  94. cout << endl <<"Info: PlannerH -> Plan (B) Path With Size (" << (int)path.size() << "), MultiPaths No(" << paths.size() << ") Extraction Time : " << endl;
  95. //PlanningHelpers::CreateManualBranch(path, 0, FORWARD_RIGHT_DIR);
  96. //cout << "Right Branch Created with Size: " << path.size() << endl;
  97. //PlanningHelpers::CreateManualBranch(path, 0, FORWARD_LEFT_DIR);
  98. paths.push_back(path);
  99. if(path.size()<2)
  100. {
  101. cout << endl << "Err: PlannerH -> Invalid Path, Car Should Stop." << endl;
  102. if(pLaneCell)
  103. DeleteWaypoints(local_cell_to_delete);
  104. return 0 ;
  105. }
  106. if(pLaneCell)
  107. DeleteWaypoints(local_cell_to_delete);
  108. double totalPlanningDistance = path.at(path.size()-1).cost;
  109. return totalPlanningDistance;
  110. }
  111. double PlannerH::PlanUsingDP(const WayPoint& start,
  112. const WayPoint& goalPos,
  113. const double& maxPlanningDistance,
  114. const bool bEnableLaneChange,
  115. const std::vector<int>& globalPath,
  116. RoadNetwork& map,
  117. std::vector<std::vector<WayPoint> >& paths, vector<WayPoint*>* all_cell_to_delete)
  118. {
  119. PlannerHNS::WayPoint* pStart = PlannerHNS::MappingHelpers::GetClosestWaypointFromMap(start, map);
  120. PlannerHNS::WayPoint* pGoal = PlannerHNS::MappingHelpers::GetClosestWaypointFromMap(goalPos, map);
  121. bool bEnableGoalBranching = false;
  122. std::cout<<" Finding Near"<<std::endl;
  123. if(!pStart || !pGoal)
  124. {
  125. GPSPoint sp = start.pos;
  126. GPSPoint gp = goalPos.pos;
  127. cout << endl << "Error: PlannerH -> Can't Find Global Waypoint Nodes in the Map for Start (" << sp.ToString() << ") and Goal (" << gp.ToString() << ")" << endl;
  128. return 0;
  129. }
  130. std::cout<<"Found Near."<<std::endl;
  131. if(!pStart->pLane || !pGoal->pLane)
  132. {
  133. cout << endl << "Error: PlannerH -> Null Lane, Start (" << pStart->pLane << ") and Goal (" << pGoal->pLane << ")" << endl;
  134. return 0;
  135. }
  136. RelativeInfo start_info, goal_info;
  137. PlanningHelpers::GetRelativeInfo(pStart->pLane->points, start, start_info);
  138. PlanningHelpers::GetRelativeInfo(pGoal->pLane->points, goalPos, goal_info);
  139. vector<WayPoint> start_path, goal_path;
  140. if(fabs(start_info.perp_distance) > START_POINT_MAX_DISTANCE)
  141. {
  142. GPSPoint sp = start.pos;
  143. cout << endl << "Error: PlannerH -> Start Distance to Lane is: " << start_info.perp_distance
  144. << ", Pose: " << sp.ToString() << ", LanePose:" << start_info.perp_point.pos.ToString()
  145. << ", LaneID: " << pStart->pLane->id << " -> Check origin and vector map. " << endl;
  146. return 0;
  147. }
  148. if(fabs(goal_info.perp_distance) > GOAL_POINT_MAX_DISTANCE)
  149. {
  150. if(fabs(start_info.perp_distance) > 20)
  151. {
  152. GPSPoint gp = goalPos.pos;
  153. cout << endl << "Error: PlannerH -> Goal Distance to Lane is: " << goal_info.perp_distance
  154. << ", Pose: " << gp.ToString() << ", LanePose:" << goal_info.perp_point.pos.ToString()
  155. << ", LaneID: " << pGoal->pLane->id << " -> Check origin and vector map. " << endl;
  156. return 0;
  157. }
  158. else
  159. {
  160. WayPoint wp = *pGoal;
  161. wp.pos.x = (goalPos.pos.x+pGoal->pos.x)/2.0;
  162. wp.pos.y = (goalPos.pos.y+pGoal->pos.y)/2.0;
  163. goal_path.push_back(wp);
  164. goal_path.push_back(goalPos);
  165. }
  166. }
  167. vector<WayPoint*> local_cell_to_delete;
  168. WayPoint* pLaneCell = 0;
  169. char bPlan = 'A';
  170. if(all_cell_to_delete)
  171. pLaneCell = PlanningHelpers::BuildPlanningSearchTreeV2(pStart, *pGoal, globalPath, maxPlanningDistance,bEnableLaneChange, *all_cell_to_delete);
  172. else
  173. pLaneCell = PlanningHelpers::BuildPlanningSearchTreeV2(pStart, *pGoal, globalPath, maxPlanningDistance,bEnableLaneChange, local_cell_to_delete);
  174. if(!pLaneCell)
  175. {
  176. bPlan = 'B';
  177. cout << endl << "PlannerH -> Plan (A) Failed, Trying Plan (B)." << endl;
  178. if(all_cell_to_delete)
  179. pLaneCell = PlanningHelpers::BuildPlanningSearchTreeStraight(pStart, BACKUP_STRAIGHT_PLAN_DISTANCE, *all_cell_to_delete);
  180. else
  181. pLaneCell = PlanningHelpers::BuildPlanningSearchTreeStraight(pStart, BACKUP_STRAIGHT_PLAN_DISTANCE, local_cell_to_delete);
  182. if(!pLaneCell)
  183. {
  184. bPlan = 'Z';
  185. cout << endl << "PlannerH -> Plan (B) Failed, Sorry we Don't have plan (C) This is the END." << endl;
  186. return 0;
  187. }
  188. }
  189. vector<WayPoint> path;
  190. vector<vector<WayPoint> > tempCurrentForwardPathss;
  191. PlanningHelpers::TraversePathTreeBackwards(pLaneCell, pStart, globalPath, path, tempCurrentForwardPathss);
  192. if(path.size()==0) return 0;
  193. paths.clear();
  194. if(bPlan == 'A')
  195. {
  196. PlanningHelpers::ExtractPlanAlernatives(path, paths);
  197. }
  198. else if (bPlan == 'B')
  199. {
  200. paths.push_back(path);
  201. }
  202. //attach start path to beginning of all paths, but goal path to only the path connected to the goal path.
  203. for(unsigned int i=0; i< paths.size(); i++ )
  204. {
  205. paths.at(i).insert(paths.at(i).begin(), start_path.begin(), start_path.end());
  206. if(paths.at(i).size() > 0)
  207. {
  208. //if(hypot(paths.at(i).at(paths.at(i).size()-1).pos.y-goal_info.perp_point.pos.y, paths.at(i).at(paths.at(i).size()-1).pos.x-goal_info.perp_point.pos.x) < 1.5)
  209. {
  210. if(paths.at(i).size() > 0 && goal_path.size() > 0)
  211. {
  212. goal_path.insert(goal_path.begin(), paths.at(i).end()-5, paths.at(i).end());
  213. PlanningHelpers::SmoothPath(goal_path, 0.25, 0.25);
  214. PlanningHelpers::FixPathDensity(goal_path, 0.75);
  215. PlanningHelpers::SmoothPath(goal_path, 0.25, 0.35);
  216. paths.at(i).erase(paths.at(i).end()-5, paths.at(i).end());
  217. paths.at(i).insert(paths.at(i).end(), goal_path.begin(), goal_path.end());
  218. }
  219. }
  220. }
  221. }
  222. cout << endl <<"Info: PlannerH -> Plan (" << bPlan << ") Path With Size (" << (int)path.size() << "), MultiPaths No(" << paths.size() << ") Extraction Time : " << endl;
  223. if(path.size()<2)
  224. {
  225. cout << endl << "Err: PlannerH -> Invalid Path, Car Should Stop." << endl;
  226. if(pLaneCell && !all_cell_to_delete)
  227. DeleteWaypoints(local_cell_to_delete);
  228. return 0 ;
  229. }
  230. if(pLaneCell && !all_cell_to_delete)
  231. DeleteWaypoints(local_cell_to_delete);
  232. double totalPlanningDistance = path.at(path.size()-1).cost;
  233. return totalPlanningDistance;
  234. }
  235. double PlannerH::PredictPlanUsingDP(PlannerHNS::Lane* l, const WayPoint& start, const double& maxPlanningDistance, std::vector<std::vector<WayPoint> >& paths)
  236. {
  237. if(!l)
  238. {
  239. cout <<endl<< "Err: PredictPlanUsingDP, PlannerH -> Null Lane !!" << endl;
  240. return 0;
  241. }
  242. WayPoint carPos = start;
  243. vector<vector<WayPoint> > tempCurrentForwardPathss;
  244. vector<WayPoint*> all_cell_to_delete;
  245. vector<int> globalPath;
  246. RelativeInfo info;
  247. PlanningHelpers::GetRelativeInfo(l->points, carPos, info);
  248. WayPoint closest_p = l->points.at(info.iBack);
  249. WayPoint* pStartWP = &l->points.at(info.iBack);
  250. if(distance2points(closest_p.pos, carPos.pos) > 8)
  251. {
  252. cout <<endl<< "Err: PredictiveDP PlannerH -> Distance to Lane is: " << distance2points(closest_p.pos, carPos.pos)
  253. << ", Pose: " << carPos.pos.ToString() << ", LanePose:" << closest_p.pos.ToString()
  254. << ", LaneID: " << l->id << " -> Check origin and vector map. " << endl;
  255. return 0;
  256. }
  257. vector<WayPoint*> pLaneCells;
  258. int nPaths = PlanningHelpers::PredictiveDP(pStartWP, maxPlanningDistance, all_cell_to_delete, pLaneCells);
  259. if(nPaths==0)
  260. {
  261. cout <<endl<< "Err PlannerH -> Null Tree Head." << endl;
  262. return 0;
  263. }
  264. double totalPlanDistance = 0;
  265. for(unsigned int i = 0; i< pLaneCells.size(); i++)
  266. {
  267. std::vector<WayPoint> path;
  268. PlanningHelpers::TraversePathTreeBackwards(pLaneCells.at(i), pStartWP, globalPath, path, tempCurrentForwardPathss);
  269. if(path.size()>0)
  270. totalPlanDistance+= path.at(path.size()-1).cost;
  271. PlanningHelpers::FixPathDensity(path, 0.5);
  272. PlanningHelpers::SmoothPath(path, 0.3 , 0.3,0.1);
  273. PlanningHelpers::CalcAngleAndCost(path);
  274. paths.push_back(path);
  275. }
  276. DeleteWaypoints(all_cell_to_delete);
  277. return totalPlanDistance;
  278. }
  279. double PlannerH::PredictTrajectoriesUsingDP(const WayPoint& startPose, std::vector<WayPoint*> closestWPs, const double& maxPlanningDistance, std::vector<std::vector<WayPoint> >& paths, const bool& bFindBranches , const bool bDirectionBased, const bool pathDensity)
  280. {
  281. vector<vector<WayPoint> > tempCurrentForwardPathss;
  282. vector<WayPoint*> all_cell_to_delete;
  283. vector<int> globalPath;
  284. vector<WayPoint*> pLaneCells;
  285. vector<int> unique_lanes;
  286. std::vector<WayPoint> path;
  287. for(unsigned int j = 0 ; j < closestWPs.size(); j++)
  288. {
  289. pLaneCells.clear();
  290. int nPaths = PlanningHelpers::PredictiveIgnorIdsDP(closestWPs.at(j), maxPlanningDistance, all_cell_to_delete, pLaneCells, unique_lanes);
  291. for(unsigned int i = 0; i< pLaneCells.size(); i++)
  292. {
  293. path.clear();
  294. PlanningHelpers::TraversePathTreeBackwards(pLaneCells.at(i), closestWPs.at(j), globalPath, path, tempCurrentForwardPathss);
  295. for(unsigned int k = 0; k< path.size(); k++)
  296. {
  297. bool bFoundLaneID = false;
  298. for(unsigned int l_id = 0 ; l_id < unique_lanes.size(); l_id++)
  299. {
  300. if(path.at(k).laneId == unique_lanes.at(l_id))
  301. {
  302. bFoundLaneID = true;
  303. break;
  304. }
  305. }
  306. if(!bFoundLaneID)
  307. unique_lanes.push_back(path.at(k).laneId);
  308. }
  309. if(path.size()>0)
  310. {
  311. path.insert(path.begin(), startPose);
  312. if(!bDirectionBased)
  313. path.at(0).pos.a = path.at(1).pos.a;
  314. path.at(0).beh_state = path.at(1).beh_state = PlannerHNS::BEH_FORWARD_STATE;
  315. path.at(0).laneId = path.at(1).laneId;
  316. PlanningHelpers::FixPathDensity(path, pathDensity);
  317. PlanningHelpers::SmoothPath(path,0.4,0.3,0.1);
  318. PlanningHelpers::CalcAngleAndCost(path);
  319. paths.push_back(path);
  320. }
  321. }
  322. }
  323. if(bDirectionBased && bFindBranches)
  324. {
  325. WayPoint p1, p2;
  326. if(paths.size()> 0 && paths.at(0).size() > 0)
  327. p2 = p1 = paths.at(0).at(0);
  328. else
  329. p2 = p1 = startPose;
  330. double branch_length = maxPlanningDistance*0.5;
  331. p2.pos.y = p1.pos.y + branch_length*0.4*sin(p1.pos.a);
  332. p2.pos.x = p1.pos.x + branch_length*0.4*cos(p1.pos.a);
  333. vector<WayPoint> l_branch;
  334. vector<WayPoint> r_branch;
  335. PlanningHelpers::CreateManualBranchFromTwoPoints(p1, p2, branch_length, FORWARD_RIGHT_DIR,r_branch);
  336. PlanningHelpers::CreateManualBranchFromTwoPoints(p1, p2, branch_length, FORWARD_LEFT_DIR, l_branch);
  337. PlanningHelpers::FixPathDensity(l_branch, pathDensity);
  338. PlanningHelpers::SmoothPath(l_branch,0.4,0.3,0.1);
  339. PlanningHelpers::CalcAngleAndCost(l_branch);
  340. PlanningHelpers::FixPathDensity(r_branch, pathDensity);
  341. PlanningHelpers::SmoothPath(r_branch,0.4,0.3,0.1);
  342. PlanningHelpers::CalcAngleAndCost(r_branch);
  343. paths.push_back(l_branch);
  344. paths.push_back(r_branch);
  345. }
  346. DeleteWaypoints(all_cell_to_delete);
  347. return paths.size();
  348. }
  349. double PlannerH::PredictPlanUsingDP(const WayPoint& startPose, WayPoint* closestWP, const double& maxPlanningDistance, std::vector<std::vector<WayPoint> >& paths, const bool& bFindBranches)
  350. {
  351. if(!closestWP || !closestWP->pLane)
  352. {
  353. cout <<endl<< "Err: PredictPlanUsingDP, PlannerH -> Null Lane !!" << endl;
  354. return 0;
  355. }
  356. vector<vector<WayPoint> > tempCurrentForwardPathss;
  357. vector<WayPoint*> all_cell_to_delete;
  358. vector<int> globalPath;
  359. vector<WayPoint*> pLaneCells;
  360. int nPaths = PlanningHelpers::PredictiveDP(closestWP, maxPlanningDistance, all_cell_to_delete, pLaneCells);
  361. if(nPaths==0)
  362. {
  363. cout <<endl<< "Err PlannerH -> Null Tree Head." << endl;
  364. return 0;
  365. }
  366. double totalPlanDistance = 0;
  367. for(unsigned int i = 0; i< pLaneCells.size(); i++)
  368. {
  369. std::vector<WayPoint> path;
  370. PlanningHelpers::TraversePathTreeBackwards(pLaneCells.at(i), closestWP, globalPath, path, tempCurrentForwardPathss);
  371. if(path.size()>0)
  372. {
  373. totalPlanDistance+= path.at(path.size()-1).cost;
  374. path.insert(path.begin(), startPose);
  375. //path.at(0).pos.a = path.at(1).pos.a;;
  376. }
  377. PlanningHelpers::FixPathDensity(path, 0.5);
  378. PlanningHelpers::SmoothPath(path, 0.3 , 0.3,0.1);
  379. paths.push_back(path);
  380. if(bFindBranches)
  381. {
  382. int max_branch_index = path.size() > 5 ? 5 : path.size();
  383. vector<WayPoint> l_branch;
  384. vector<WayPoint> r_branch;
  385. l_branch.insert(l_branch.begin(), path.begin(), path.begin()+5);
  386. r_branch.insert(r_branch.begin(), path.begin(), path.begin()+5);
  387. PlanningHelpers::CreateManualBranch(r_branch, 0, FORWARD_RIGHT_DIR);
  388. PlanningHelpers::CreateManualBranch(l_branch, 0, FORWARD_LEFT_DIR);
  389. paths.push_back(l_branch);
  390. paths.push_back(r_branch);
  391. }
  392. }
  393. DeleteWaypoints(all_cell_to_delete);
  394. return totalPlanDistance;
  395. }
  396. void PlannerH::DeleteWaypoints(vector<WayPoint*>& wps)
  397. {
  398. for(unsigned int i=0; i<wps.size(); i++)
  399. {
  400. if(wps.at(i))
  401. {
  402. delete wps.at(i);
  403. wps.at(i) = 0;
  404. }
  405. }
  406. wps.clear();
  407. }
  408. }