TrajectoryCosts.cpp 15 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390
  1. /// \file TrajectoryCosts.cpp
  2. /// \brief Calculate collision costs for roll out trajectory for free trajectory evaluation for dp_planner
  3. /// \author Hatem Darweesh
  4. /// \date Dec 14, 2016
  5. #include "op_planner/TrajectoryCosts.h"
  6. #include "op_planner/MatrixOperations.h"
  7. #include "float.h"
  8. namespace PlannerHNS
  9. {
  10. TrajectoryCosts::TrajectoryCosts()
  11. {
  12. m_PrevCostIndex = -1;
  13. m_WeightPriority = 0.125;
  14. m_WeightTransition = 0.13;
  15. m_WeightLong = 1.0;
  16. m_WeightLat = 1.0;
  17. m_WeightLaneChange = 1.0;
  18. m_LateralSkipDistance = 10;
  19. }
  20. TrajectoryCosts::~TrajectoryCosts()
  21. {
  22. }
  23. TrajectoryCost TrajectoryCosts::DoOneStep(const vector<vector<vector<WayPoint> > >& rollOuts,
  24. const vector<vector<WayPoint> >& totalPaths, const WayPoint& currState, const int& currIndex,
  25. const int& currLaneIndex,
  26. const PlanningParams& params, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState,
  27. const std::vector<PlannerHNS::DetectedObject>& obj_list)
  28. {
  29. TrajectoryCost bestTrajectory;
  30. bestTrajectory.bBlocked = true;
  31. bestTrajectory.closest_obj_distance = params.horizonDistance;
  32. bestTrajectory.closest_obj_velocity = 0;
  33. bestTrajectory.index = -1;
  34. if(!ValidateRollOutsInput(rollOuts) || rollOuts.size() != totalPaths.size()) return bestTrajectory;
  35. if(m_PrevCostIndex == -1)
  36. m_PrevCostIndex = params.rollOutNumber/2;
  37. m_TrajectoryCosts.clear();
  38. for(unsigned int il = 0; il < rollOuts.size(); il++)
  39. {
  40. if(rollOuts.at(il).size()>0 && rollOuts.at(il).at(0).size()>0)
  41. {
  42. vector<TrajectoryCost> costs = CalculatePriorityAndLaneChangeCosts(rollOuts.at(il), il, params);
  43. m_TrajectoryCosts.insert(m_TrajectoryCosts.end(), costs.begin(), costs.end());
  44. }
  45. }
  46. CalculateTransitionCosts(m_TrajectoryCosts, currIndex, params);
  47. WayPoint p;
  48. m_AllContourPoints.clear();
  49. for(unsigned int io=0; io<obj_list.size(); io++)
  50. {
  51. for(unsigned int icon=0; icon < obj_list.at(io).contour.size(); icon++)
  52. {
  53. p.pos = obj_list.at(io).contour.at(icon);
  54. p.v = obj_list.at(io).center.v;
  55. p.id = io;
  56. p.cost = sqrt(obj_list.at(io).w*obj_list.at(io).w + obj_list.at(io).l*obj_list.at(io).l);
  57. m_AllContourPoints.push_back(p);
  58. }
  59. }
  60. CalculateLateralAndLongitudinalCosts(m_TrajectoryCosts, rollOuts, totalPaths, currState, m_AllContourPoints, params, carInfo, vehicleState);
  61. NormalizeCosts(m_TrajectoryCosts);
  62. int smallestIndex = -1;
  63. double smallestCost = DBL_MAX;
  64. double smallestDistance = DBL_MAX;
  65. double velo_of_next = 0;
  66. //cout << "Trajectory Costs Log : CurrIndex: " << currIndex << " --------------------- " << endl;
  67. for(unsigned int ic = 0; ic < m_TrajectoryCosts.size(); ic++)
  68. {
  69. //cout << m_TrajectoryCosts.at(ic).ToString();
  70. if(!m_TrajectoryCosts.at(ic).bBlocked && m_TrajectoryCosts.at(ic).cost < smallestCost)
  71. {
  72. smallestCost = m_TrajectoryCosts.at(ic).cost;
  73. smallestIndex = ic;
  74. }
  75. if(m_TrajectoryCosts.at(ic).closest_obj_distance < smallestDistance)
  76. {
  77. smallestDistance = m_TrajectoryCosts.at(ic).closest_obj_distance;
  78. velo_of_next = m_TrajectoryCosts.at(ic).closest_obj_velocity;
  79. }
  80. }
  81. //cout << "Smallest Distance: " << smallestDistance << "------------------------------------------------------------- " << endl;
  82. //All is blocked !
  83. if(smallestIndex == -1 && m_PrevCostIndex < (int)m_TrajectoryCosts.size())
  84. {
  85. bestTrajectory.bBlocked = true;
  86. bestTrajectory.lane_index = currLaneIndex;
  87. bestTrajectory.index = currIndex;
  88. bestTrajectory.closest_obj_distance = smallestDistance;
  89. bestTrajectory.closest_obj_velocity = velo_of_next;
  90. //bestTrajectory.index = smallestIndex;
  91. }
  92. else if(smallestIndex >= 0)
  93. {
  94. bestTrajectory = m_TrajectoryCosts.at(smallestIndex);
  95. //bestTrajectory.index = smallestIndex;
  96. }
  97. // cout << "smallestI: " << smallestIndex << ", C_Size: " << m_TrajectoryCosts.size()
  98. // << ", LaneI: " << bestTrajectory.lane_index << "TrajI: " << bestTrajectory.index
  99. // << ", prevSmalI: " << m_PrevCostIndex << ", distance: " << bestTrajectory.closest_obj_distance
  100. // << ", Blocked: " << bestTrajectory.bBlocked
  101. // << endl;
  102. m_PrevCostIndex = smallestIndex;
  103. return bestTrajectory;
  104. }
  105. void TrajectoryCosts::CalculateLateralAndLongitudinalCosts(vector<TrajectoryCost>& trajectoryCosts,
  106. const vector<vector<vector<WayPoint> > >& rollOuts, const vector<vector<WayPoint> >& totalPaths,
  107. const WayPoint& currState, const vector<WayPoint>& contourPoints, const PlanningParams& params,
  108. const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState)
  109. {
  110. double critical_lateral_distance = carInfo.width/2.0 + params.horizontalSafetyDistancel;
  111. double critical_long_front_distance = carInfo.wheel_base/2.0 + carInfo.length/2.0 + params.verticalSafetyDistance;
  112. double critical_long_back_distance = carInfo.length/2.0 + params.verticalSafetyDistance - carInfo.wheel_base/2.0;
  113. int iCostIndex = 0;
  114. PlannerHNS::Mat3 invRotationMat(currState.pos.a-M_PI_2);
  115. PlannerHNS::Mat3 invTranslationMat(currState.pos.x, currState.pos.y);
  116. double corner_slide_distance = critical_lateral_distance/2.0;
  117. double ratio_to_angle = corner_slide_distance/carInfo.max_steer_angle;
  118. double slide_distance = vehicleState.steer * ratio_to_angle;
  119. GPSPoint bottom_left(-critical_lateral_distance ,-critical_long_back_distance, currState.pos.z, 0);
  120. GPSPoint bottom_right(critical_lateral_distance, -critical_long_back_distance, currState.pos.z, 0);
  121. GPSPoint top_right_car(critical_lateral_distance, carInfo.wheel_base/3.0 + carInfo.length/3.0, currState.pos.z, 0);
  122. GPSPoint top_left_car(-critical_lateral_distance, carInfo.wheel_base/3.0 + carInfo.length/3.0, currState.pos.z, 0);
  123. GPSPoint top_right(critical_lateral_distance - slide_distance, critical_long_front_distance, currState.pos.z, 0);
  124. GPSPoint top_left(-critical_lateral_distance - slide_distance , critical_long_front_distance, currState.pos.z, 0);
  125. bottom_left = invRotationMat*bottom_left;
  126. bottom_left = invTranslationMat*bottom_left;
  127. top_right = invRotationMat*top_right;
  128. top_right = invTranslationMat*top_right;
  129. bottom_right = invRotationMat*bottom_right;
  130. bottom_right = invTranslationMat*bottom_right;
  131. top_left = invRotationMat*top_left;
  132. top_left = invTranslationMat*top_left;
  133. top_right_car = invRotationMat*top_right_car;
  134. top_right_car = invTranslationMat*top_right_car;
  135. top_left_car = invRotationMat*top_left_car;
  136. top_left_car = invTranslationMat*top_left_car;
  137. m_SafetyBorder.points.clear();
  138. m_SafetyBorder.points.push_back(bottom_left) ;
  139. m_SafetyBorder.points.push_back(bottom_right) ;
  140. m_SafetyBorder.points.push_back(top_right_car) ;
  141. m_SafetyBorder.points.push_back(top_right) ;
  142. m_SafetyBorder.points.push_back(top_left) ;
  143. m_SafetyBorder.points.push_back(top_left_car) ;
  144. for(unsigned int il=0; il < rollOuts.size(); il++)
  145. {
  146. if(rollOuts.at(il).size() > 0 && rollOuts.at(il).at(0).size()>0)
  147. {
  148. RelativeInfo car_info;
  149. PlanningHelpers::GetRelativeInfo(totalPaths.at(il), currState, car_info);
  150. for(unsigned int it=0; it< rollOuts.at(il).size(); it++)
  151. {
  152. int skip_id = -1;
  153. for(unsigned int icon = 0; icon < contourPoints.size(); icon++)
  154. {
  155. if(skip_id == contourPoints.at(icon).id)
  156. continue;
  157. RelativeInfo obj_info;
  158. PlanningHelpers::GetRelativeInfo(totalPaths.at(il), contourPoints.at(icon), obj_info);
  159. double longitudinalDist = PlanningHelpers::GetExactDistanceOnTrajectory(totalPaths.at(il), car_info, obj_info);
  160. if(obj_info.iFront == 0 && longitudinalDist > 0)
  161. longitudinalDist = -longitudinalDist;
  162. double direct_distance = hypot(obj_info.perp_point.pos.y-contourPoints.at(icon).pos.y, obj_info.perp_point.pos.x-contourPoints.at(icon).pos.x);
  163. if(contourPoints.at(icon).v < params.minSpeed && direct_distance > (m_LateralSkipDistance+contourPoints.at(icon).cost))
  164. {
  165. skip_id = contourPoints.at(icon).id;
  166. continue;
  167. }
  168. double close_in_percentage = 1;
  169. // close_in_percentage = ((longitudinalDist- critical_long_front_distance)/params.rollInMargin)*4.0;
  170. //
  171. // if(close_in_percentage <= 0 || close_in_percentage > 1) close_in_percentage = 1;
  172. double distance_from_center = trajectoryCosts.at(iCostIndex).distance_from_center;
  173. if(close_in_percentage < 1)
  174. distance_from_center = distance_from_center - distance_from_center * (1.0-close_in_percentage);
  175. double lateralDist = fabs(obj_info.perp_distance - distance_from_center);
  176. if(longitudinalDist < -carInfo.length || longitudinalDist > params.minFollowingDistance || lateralDist > m_LateralSkipDistance)
  177. {
  178. continue;
  179. }
  180. longitudinalDist = longitudinalDist - critical_long_front_distance;
  181. if(m_SafetyBorder.PointInsidePolygon(m_SafetyBorder, contourPoints.at(icon).pos) == true)
  182. trajectoryCosts.at(iCostIndex).bBlocked = true;
  183. if(lateralDist <= critical_lateral_distance
  184. && longitudinalDist >= -carInfo.length/1.5
  185. && longitudinalDist < params.minFollowingDistance)
  186. trajectoryCosts.at(iCostIndex).bBlocked = true;
  187. if(lateralDist != 0)
  188. trajectoryCosts.at(iCostIndex).lateral_cost += 1.0/lateralDist;
  189. if(longitudinalDist != 0)
  190. trajectoryCosts.at(iCostIndex).longitudinal_cost += 1.0/fabs(longitudinalDist);
  191. if(longitudinalDist >= -critical_long_front_distance && longitudinalDist < trajectoryCosts.at(iCostIndex).closest_obj_distance)
  192. {
  193. trajectoryCosts.at(iCostIndex).closest_obj_distance = longitudinalDist;
  194. trajectoryCosts.at(iCostIndex).closest_obj_velocity = contourPoints.at(icon).v;
  195. }
  196. }
  197. iCostIndex++;
  198. }
  199. }
  200. }
  201. }
  202. void TrajectoryCosts::NormalizeCosts(vector<TrajectoryCost>& trajectoryCosts)
  203. {
  204. //Normalize costs
  205. double totalPriorities = 0;
  206. double totalChange = 0;
  207. double totalLateralCosts = 0;
  208. double totalLongitudinalCosts = 0;
  209. double transitionCosts = 0;
  210. for(unsigned int ic = 0; ic< trajectoryCosts.size(); ic++)
  211. {
  212. totalPriorities += trajectoryCosts.at(ic).priority_cost;
  213. transitionCosts += trajectoryCosts.at(ic).transition_cost;
  214. }
  215. for(unsigned int ic = 0; ic< trajectoryCosts.size(); ic++)
  216. {
  217. totalChange += trajectoryCosts.at(ic).lane_change_cost;
  218. totalLateralCosts += trajectoryCosts.at(ic).lateral_cost;
  219. totalLongitudinalCosts += trajectoryCosts.at(ic).longitudinal_cost;
  220. }
  221. // cout << "------ Normalizing Step " << endl;
  222. for(unsigned int ic = 0; ic< trajectoryCosts.size(); ic++)
  223. {
  224. if(totalPriorities != 0)
  225. trajectoryCosts.at(ic).priority_cost = trajectoryCosts.at(ic).priority_cost / totalPriorities;
  226. else
  227. trajectoryCosts.at(ic).priority_cost = 0;
  228. if(transitionCosts != 0)
  229. trajectoryCosts.at(ic).transition_cost = trajectoryCosts.at(ic).transition_cost / transitionCosts;
  230. else
  231. trajectoryCosts.at(ic).transition_cost = 0;
  232. if(totalChange != 0)
  233. trajectoryCosts.at(ic).lane_change_cost = trajectoryCosts.at(ic).lane_change_cost / totalChange;
  234. else
  235. trajectoryCosts.at(ic).lane_change_cost = 0;
  236. if(totalLateralCosts != 0)
  237. trajectoryCosts.at(ic).lateral_cost = trajectoryCosts.at(ic).lateral_cost / totalLateralCosts;
  238. else
  239. trajectoryCosts.at(ic).lateral_cost = 0;
  240. if(totalLongitudinalCosts != 0)
  241. trajectoryCosts.at(ic).longitudinal_cost = trajectoryCosts.at(ic).longitudinal_cost / totalLongitudinalCosts;
  242. else
  243. trajectoryCosts.at(ic).longitudinal_cost = 0;
  244. trajectoryCosts.at(ic).priority_cost = m_WeightPriority*trajectoryCosts.at(ic).priority_cost;
  245. trajectoryCosts.at(ic).transition_cost = m_WeightTransition*trajectoryCosts.at(ic).transition_cost;
  246. trajectoryCosts.at(ic).lane_change_cost = m_WeightLaneChange*trajectoryCosts.at(ic).lane_change_cost;
  247. trajectoryCosts.at(ic).lateral_cost = m_WeightLat*trajectoryCosts.at(ic).lateral_cost;
  248. trajectoryCosts.at(ic).longitudinal_cost = m_WeightLong*trajectoryCosts.at(ic).longitudinal_cost;
  249. trajectoryCosts.at(ic).cost = m_WeightPriority*trajectoryCosts.at(ic).priority_cost/5.0 +
  250. m_WeightLaneChange*trajectoryCosts.at(ic).lane_change_cost/5.0 +
  251. m_WeightLat*trajectoryCosts.at(ic).lateral_cost/5.0 +
  252. m_WeightLong*trajectoryCosts.at(ic).longitudinal_cost/5.0 +
  253. m_WeightTransition*trajectoryCosts.at(ic).transition_cost/5.0;
  254. // cout << "Index: " << ic
  255. // << ", Priority: " << trajectoryCosts.at(ic).priority_cost
  256. // << ", Transition: " << trajectoryCosts.at(ic).transition_cost
  257. // << ", Lat: " << trajectoryCosts.at(ic).lateral_cost
  258. // << ", Long: " << trajectoryCosts.at(ic).longitudinal_cost
  259. // << ", Change: " << trajectoryCosts.at(ic).lane_change_cost
  260. // << ", Avg: " << trajectoryCosts.at(ic).cost
  261. // << endl;
  262. }
  263. // cout << "------------------------ " << endl;
  264. }
  265. vector<TrajectoryCost> TrajectoryCosts::CalculatePriorityAndLaneChangeCosts(const vector<vector<WayPoint> >& laneRollOuts,
  266. const int& lane_index, const PlanningParams& params)
  267. {
  268. vector<TrajectoryCost> costs;
  269. TrajectoryCost tc;
  270. int centralIndex = params.rollOutNumber/2;
  271. tc.lane_index = lane_index;
  272. for(unsigned int it=0; it< laneRollOuts.size(); it++)
  273. {
  274. tc.index = it;
  275. tc.relative_index = it - centralIndex;
  276. tc.distance_from_center = params.rollOutDensity*tc.relative_index;
  277. tc.priority_cost = fabs(tc.distance_from_center);
  278. tc.closest_obj_distance = params.horizonDistance;
  279. tc.lane_change_cost = laneRollOuts.at(it).at(0).laneChangeCost;
  280. // if(laneRollOuts.at(it).at(0).bDir == FORWARD_LEFT_DIR || laneRollOuts.at(it).at(0).bDir == FORWARD_RIGHT_DIR)
  281. // tc.lane_change_cost = 1;
  282. // else if(laneRollOuts.at(it).at(0).bDir == BACKWARD_DIR || laneRollOuts.at(it).at(0).bDir == BACKWARD_RIGHT_DIR || laneRollOuts.at(it).at(0).bDir == BACKWARD_LEFT_DIR)
  283. // tc.lane_change_cost = 2;
  284. // else
  285. // tc.lane_change_cost = 0;
  286. costs.push_back(tc);
  287. }
  288. return costs;
  289. }
  290. void TrajectoryCosts::CalculateTransitionCosts(vector<TrajectoryCost>& trajectoryCosts, const int& currTrajectoryIndex, const PlanningParams& params)
  291. {
  292. for(int ic = 0; ic< trajectoryCosts.size(); ic++)
  293. {
  294. trajectoryCosts.at(ic).transition_cost = fabs(params.rollOutDensity * (ic - currTrajectoryIndex));
  295. }
  296. }
  297. /**
  298. * @brief Validate input, each trajectory must have at least 1 way point
  299. * @param rollOuts
  300. * @return true if data isvalid for cost calculation
  301. */
  302. bool TrajectoryCosts::ValidateRollOutsInput(const vector<vector<vector<WayPoint> > >& rollOuts)
  303. {
  304. if(rollOuts.size()==0)
  305. return false;
  306. for(unsigned int il = 0; il < rollOuts.size(); il++)
  307. {
  308. if(rollOuts.at(il).size() == 0)
  309. return false;
  310. }
  311. return true;
  312. }
  313. }