TrajectoryDynamicCosts.cpp 35 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917
  1. /// \file TrajectoryDynamicCosts.cpp
  2. /// \brief Calculate collision costs for roll out trajectory for free trajectory evaluation for OpenPlanner local planner version 1.5+
  3. /// \author Hatem Darweesh
  4. /// \date Jan 14, 2018
  5. #include "op_planner/TrajectoryDynamicCosts.h"
  6. #include "op_planner/MatrixOperations.h"
  7. #include "float.h"
  8. namespace PlannerHNS
  9. {
  10. TrajectoryDynamicCosts::TrajectoryDynamicCosts()
  11. {
  12. m_PrevCostIndex = -1;
  13. //m_WeightPriority = 0.125;
  14. //m_WeightTransition = 0.13;
  15. m_WeightLong = 1.0;
  16. m_WeightLat = 1.2;
  17. m_WeightLaneChange = 0.0;
  18. m_LateralSkipDistance = 50;
  19. m_CollisionTimeDiff = 6.0; //seconds
  20. m_PrevIndex = -1;
  21. m_WeightPriority = 0.9;
  22. m_WeightTransition = 0.9;
  23. }
  24. TrajectoryDynamicCosts::~TrajectoryDynamicCosts()
  25. {
  26. }
  27. TrajectoryCost TrajectoryDynamicCosts::DoOneStepDynamic(const vector<vector<WayPoint> >& rollOuts,
  28. const vector<WayPoint>& totalPaths, const WayPoint& currState,
  29. const PlanningParams& params, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState,
  30. const std::vector<PlannerHNS::DetectedObject>& obj_list, const int& iCurrentIndex)
  31. {
  32. TrajectoryCost bestTrajectory;
  33. bestTrajectory.bBlocked = true;
  34. bestTrajectory.closest_obj_distance = params.horizonDistance;
  35. bestTrajectory.closest_obj_velocity = 0;
  36. bestTrajectory.index = -1;
  37. double critical_lateral_distance = carInfo.width/2.0 + params.horizontalSafetyDistancel;
  38. double critical_long_front_distance = carInfo.wheel_base/2.0 + carInfo.length/2.0 + params.verticalSafetyDistance;
  39. double critical_long_back_distance = carInfo.length/2.0 + params.verticalSafetyDistance - carInfo.wheel_base/2.0;
  40. int currIndex = -1;
  41. if(iCurrentIndex >=0 && iCurrentIndex < rollOuts.size())
  42. currIndex = iCurrentIndex;
  43. else
  44. currIndex = GetCurrentRollOutIndex(totalPaths, currState, params);
  45. InitializeCosts(rollOuts, params);
  46. InitializeSafetyPolygon(currState, carInfo, vehicleState, critical_lateral_distance, critical_long_front_distance, critical_long_back_distance);
  47. CalculateTransitionCosts(m_TrajectoryCosts, currIndex, params);
  48. CalculateLateralAndLongitudinalCostsDynamic(obj_list, rollOuts, totalPaths, currState, params, carInfo, vehicleState, critical_lateral_distance, critical_long_front_distance, critical_long_back_distance);
  49. NormalizeCosts(m_TrajectoryCosts);
  50. int smallestIndex = -1;
  51. double smallestCost = DBL_MAX;
  52. double smallestDistance = DBL_MAX;
  53. double velo_of_next = 0;
  54. bool bAllFree = true;
  55. //cout << "Trajectory Costs Log : CurrIndex: " << currIndex << " --------------------- " << endl;
  56. for(unsigned int ic = 0; ic < m_TrajectoryCosts.size(); ic++)
  57. {
  58. //cout << m_TrajectoryCosts.at(ic).ToString();
  59. if(!m_TrajectoryCosts.at(ic).bBlocked && m_TrajectoryCosts.at(ic).cost < smallestCost)
  60. {
  61. smallestCost = m_TrajectoryCosts.at(ic).cost;
  62. smallestIndex = ic;
  63. }
  64. if(m_TrajectoryCosts.at(ic).closest_obj_distance < smallestDistance)
  65. {
  66. smallestDistance = m_TrajectoryCosts.at(ic).closest_obj_distance;
  67. velo_of_next = m_TrajectoryCosts.at(ic).closest_obj_velocity;
  68. }
  69. if(m_TrajectoryCosts.at(ic).bBlocked)
  70. bAllFree = false;
  71. }
  72. //cout << "Smallest Distance: " << smallestDistance << "------------------------------------------------------------- " << endl;
  73. if(bAllFree && smallestIndex >=0)
  74. smallestIndex = params.rollOutNumber/2;
  75. if(smallestIndex == -1)
  76. {
  77. bestTrajectory.bBlocked = true;
  78. bestTrajectory.lane_index = 0;
  79. bestTrajectory.index = m_PrevCostIndex;
  80. bestTrajectory.closest_obj_distance = smallestDistance;
  81. bestTrajectory.closest_obj_velocity = velo_of_next;
  82. }
  83. else if(smallestIndex >= 0)
  84. {
  85. bestTrajectory = m_TrajectoryCosts.at(smallestIndex);
  86. }
  87. m_PrevIndex = currIndex;
  88. //std::cout << "Current Selected Index : " << bestTrajectory.index << std::endl;
  89. return bestTrajectory;
  90. }
  91. TrajectoryCost TrajectoryDynamicCosts::DoOneStepStatic(const vector<vector<WayPoint> >& rollOuts,
  92. const vector<WayPoint>& totalPaths, const WayPoint& currState,
  93. const PlanningParams& params, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState,
  94. const std::vector<PlannerHNS::DetectedObject>& obj_list, const int& iCurrentIndex)
  95. {
  96. TrajectoryCost bestTrajectory;
  97. bestTrajectory.bBlocked = true;
  98. bestTrajectory.closest_obj_distance = params.horizonDistance;
  99. bestTrajectory.closest_obj_velocity = 0;
  100. bestTrajectory.index = -1;
  101. RelativeInfo obj_info;
  102. PlanningHelpers::GetRelativeInfo(totalPaths, currState, obj_info);
  103. int currIndex = params.rollOutNumber/2 + floor(obj_info.perp_distance/params.rollOutDensity);
  104. //std::cout << "Current Index: " << currIndex << std::endl;
  105. if(currIndex < 0)
  106. currIndex = 0;
  107. else if(currIndex > params.rollOutNumber)
  108. currIndex = params.rollOutNumber;
  109. m_TrajectoryCosts.clear();
  110. if(rollOuts.size()>0)
  111. {
  112. TrajectoryCost tc;
  113. int centralIndex = params.rollOutNumber/2;
  114. tc.lane_index = 0;
  115. for(unsigned int it=0; it< rollOuts.size(); it++)
  116. {
  117. tc.index = it;
  118. tc.relative_index = it - centralIndex;
  119. tc.distance_from_center = params.rollOutDensity*tc.relative_index;
  120. tc.priority_cost = fabs(tc.distance_from_center);
  121. tc.closest_obj_distance = params.horizonDistance;
  122. if(rollOuts.at(it).size() > 0)
  123. tc.lane_change_cost = rollOuts.at(it).at(0).laneChangeCost;
  124. m_TrajectoryCosts.push_back(tc);
  125. }
  126. }
  127. CalculateTransitionCosts(m_TrajectoryCosts, currIndex, params);
  128. WayPoint p;
  129. m_AllContourPoints.clear();
  130. for(unsigned int io=0; io<obj_list.size(); io++)
  131. {
  132. for(unsigned int icon=0; icon < obj_list.at(io).contour.size(); icon++)
  133. {
  134. p.pos = obj_list.at(io).contour.at(icon);
  135. p.v = obj_list.at(io).center.v;
  136. p.id = io;
  137. p.cost = sqrt(obj_list.at(io).w*obj_list.at(io).w + obj_list.at(io).l*obj_list.at(io).l);
  138. m_AllContourPoints.push_back(p);
  139. }
  140. }
  141. CalculateLateralAndLongitudinalCostsStatic(m_TrajectoryCosts, rollOuts, totalPaths, currState, m_AllContourPoints, params, carInfo, vehicleState);
  142. NormalizeCosts(m_TrajectoryCosts);
  143. int smallestIndex = -1;
  144. double smallestCost = DBL_MAX;
  145. double smallestDistance = DBL_MAX;
  146. double velo_of_next = 0;
  147. //cout << "Trajectory Costs Log : CurrIndex: " << currIndex << " --------------------- " << endl;
  148. for(unsigned int ic = 0; ic < m_TrajectoryCosts.size(); ic++)
  149. {
  150. //cout << m_TrajectoryCosts.at(ic).ToString();
  151. if(!m_TrajectoryCosts.at(ic).bBlocked && m_TrajectoryCosts.at(ic).cost < smallestCost)
  152. {
  153. smallestCost = m_TrajectoryCosts.at(ic).cost;
  154. smallestIndex = ic;
  155. }
  156. if(m_TrajectoryCosts.at(ic).closest_obj_distance < smallestDistance)
  157. {
  158. smallestDistance = m_TrajectoryCosts.at(ic).closest_obj_distance;
  159. velo_of_next = m_TrajectoryCosts.at(ic).closest_obj_velocity;
  160. }
  161. }
  162. //cout << "Smallest Distance: " << smallestDistance << "------------------------------------------------------------- " << endl;
  163. if(smallestIndex == -1)
  164. {
  165. bestTrajectory.bBlocked = true;
  166. bestTrajectory.lane_index = 0;
  167. bestTrajectory.index = m_PrevCostIndex;
  168. bestTrajectory.closest_obj_distance = smallestDistance;
  169. bestTrajectory.closest_obj_velocity = velo_of_next;
  170. }
  171. else if(smallestIndex >= 0)
  172. {
  173. bestTrajectory = m_TrajectoryCosts.at(smallestIndex);
  174. }
  175. m_PrevIndex = currIndex;
  176. return bestTrajectory;
  177. }
  178. TrajectoryCost TrajectoryDynamicCosts::DoOneStep(const vector<vector<vector<WayPoint> > >& rollOuts,
  179. const vector<vector<WayPoint> >& totalPaths, const WayPoint& currState, const int& currIndex,
  180. const int& currLaneIndex,
  181. const PlanningParams& params, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState,
  182. const std::vector<PlannerHNS::DetectedObject>& obj_list)
  183. {
  184. TrajectoryCost bestTrajectory;
  185. bestTrajectory.bBlocked = true;
  186. bestTrajectory.closest_obj_distance = params.horizonDistance;
  187. bestTrajectory.closest_obj_velocity = 0;
  188. bestTrajectory.index = -1;
  189. if(!ValidateRollOutsInput(rollOuts) || rollOuts.size() != totalPaths.size()) return bestTrajectory;
  190. if(m_PrevCostIndex == -1)
  191. m_PrevCostIndex = params.rollOutNumber/2;
  192. m_TrajectoryCosts.clear();
  193. for(unsigned int il = 0; il < rollOuts.size(); il++)
  194. {
  195. if(rollOuts.at(il).size()>0 && rollOuts.at(il).at(0).size()>0)
  196. {
  197. vector<TrajectoryCost> costs = CalculatePriorityAndLaneChangeCosts(rollOuts.at(il), il, params);
  198. m_TrajectoryCosts.insert(m_TrajectoryCosts.end(), costs.begin(), costs.end());
  199. }
  200. }
  201. CalculateTransitionCosts(m_TrajectoryCosts, currIndex, params);
  202. WayPoint p;
  203. m_AllContourPoints.clear();
  204. for(unsigned int io=0; io<obj_list.size(); io++)
  205. {
  206. for(unsigned int icon=0; icon < obj_list.at(io).contour.size(); icon++)
  207. {
  208. p.pos = obj_list.at(io).contour.at(icon);
  209. p.v = obj_list.at(io).center.v;
  210. p.id = io;
  211. p.cost = sqrt(obj_list.at(io).w*obj_list.at(io).w + obj_list.at(io).l*obj_list.at(io).l);
  212. m_AllContourPoints.push_back(p);
  213. }
  214. }
  215. CalculateLateralAndLongitudinalCosts(m_TrajectoryCosts, rollOuts, totalPaths, currState, m_AllContourPoints, params, carInfo, vehicleState);
  216. NormalizeCosts(m_TrajectoryCosts);
  217. int smallestIndex = -1;
  218. double smallestCost = DBL_MAX;
  219. double smallestDistance = DBL_MAX;
  220. double velo_of_next = 0;
  221. //cout << "Trajectory Costs Log : CurrIndex: " << currIndex << " --------------------- " << endl;
  222. for(unsigned int ic = 0; ic < m_TrajectoryCosts.size(); ic++)
  223. {
  224. //cout << m_TrajectoryCosts.at(ic).ToString();
  225. if(!m_TrajectoryCosts.at(ic).bBlocked && m_TrajectoryCosts.at(ic).cost < smallestCost)
  226. {
  227. smallestCost = m_TrajectoryCosts.at(ic).cost;
  228. smallestIndex = ic;
  229. }
  230. if(m_TrajectoryCosts.at(ic).closest_obj_distance < smallestDistance)
  231. {
  232. smallestDistance = m_TrajectoryCosts.at(ic).closest_obj_distance;
  233. velo_of_next = m_TrajectoryCosts.at(ic).closest_obj_velocity;
  234. }
  235. }
  236. //cout << "Smallest Distance: " << smallestDistance << "------------------------------------------------------------- " << endl;
  237. //All is blocked !
  238. if(smallestIndex == -1 && m_PrevCostIndex < (int)m_TrajectoryCosts.size())
  239. {
  240. bestTrajectory.bBlocked = true;
  241. bestTrajectory.lane_index = currLaneIndex;
  242. bestTrajectory.index = currIndex;
  243. bestTrajectory.closest_obj_distance = smallestDistance;
  244. bestTrajectory.closest_obj_velocity = velo_of_next;
  245. //bestTrajectory.index = smallestIndex;
  246. }
  247. else if(smallestIndex >= 0)
  248. {
  249. bestTrajectory = m_TrajectoryCosts.at(smallestIndex);
  250. //bestTrajectory.index = smallestIndex;
  251. }
  252. // cout << "smallestI: " << smallestIndex << ", C_Size: " << m_TrajectoryCosts.size()
  253. // << ", LaneI: " << bestTrajectory.lane_index << "TrajI: " << bestTrajectory.index
  254. // << ", prevSmalI: " << m_PrevCostIndex << ", distance: " << bestTrajectory.closest_obj_distance
  255. // << ", Blocked: " << bestTrajectory.bBlocked
  256. // << endl;
  257. m_PrevCostIndex = smallestIndex;
  258. return bestTrajectory;
  259. }
  260. void TrajectoryDynamicCosts::CalculateLateralAndLongitudinalCostsStatic(vector<TrajectoryCost>& trajectoryCosts,
  261. const vector<vector<WayPoint> >& rollOuts, const vector<WayPoint>& totalPaths,
  262. const WayPoint& currState, const vector<WayPoint>& contourPoints, const PlanningParams& params,
  263. const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState)
  264. {
  265. double critical_lateral_distance = carInfo.width/2.0 + params.horizontalSafetyDistancel;
  266. double critical_long_front_distance = carInfo.wheel_base/2.0 + carInfo.length/2.0 + params.verticalSafetyDistance;
  267. double critical_long_back_distance = carInfo.length/2.0 + params.verticalSafetyDistance - carInfo.wheel_base/2.0;
  268. PlannerHNS::Mat3 invRotationMat(currState.pos.a-M_PI_2);
  269. PlannerHNS::Mat3 invTranslationMat(currState.pos.x, currState.pos.y);
  270. double corner_slide_distance = critical_lateral_distance/2.0;
  271. double ratio_to_angle = corner_slide_distance/carInfo.max_steer_angle;
  272. double slide_distance = vehicleState.steer * ratio_to_angle;
  273. GPSPoint bottom_left(-critical_lateral_distance ,-critical_long_back_distance, currState.pos.z, 0);
  274. GPSPoint bottom_right(critical_lateral_distance, -critical_long_back_distance, currState.pos.z, 0);
  275. GPSPoint top_right_car(critical_lateral_distance, carInfo.wheel_base/3.0 + carInfo.length/3.0, currState.pos.z, 0);
  276. GPSPoint top_left_car(-critical_lateral_distance, carInfo.wheel_base/3.0 + carInfo.length/3.0, currState.pos.z, 0);
  277. GPSPoint top_right(critical_lateral_distance - slide_distance, critical_long_front_distance, currState.pos.z, 0);
  278. GPSPoint top_left(-critical_lateral_distance - slide_distance , critical_long_front_distance, currState.pos.z, 0);
  279. bottom_left = invRotationMat*bottom_left;
  280. bottom_left = invTranslationMat*bottom_left;
  281. top_right = invRotationMat*top_right;
  282. top_right = invTranslationMat*top_right;
  283. bottom_right = invRotationMat*bottom_right;
  284. bottom_right = invTranslationMat*bottom_right;
  285. top_left = invRotationMat*top_left;
  286. top_left = invTranslationMat*top_left;
  287. top_right_car = invRotationMat*top_right_car;
  288. top_right_car = invTranslationMat*top_right_car;
  289. top_left_car = invRotationMat*top_left_car;
  290. top_left_car = invTranslationMat*top_left_car;
  291. m_SafetyBorder.points.clear();
  292. m_SafetyBorder.points.push_back(bottom_left) ;
  293. m_SafetyBorder.points.push_back(bottom_right) ;
  294. m_SafetyBorder.points.push_back(top_right_car) ;
  295. m_SafetyBorder.points.push_back(top_right) ;
  296. m_SafetyBorder.points.push_back(top_left) ;
  297. m_SafetyBorder.points.push_back(top_left_car) ;
  298. int iCostIndex = 0;
  299. if(rollOuts.size() > 0 && rollOuts.at(0).size()>0)
  300. {
  301. RelativeInfo car_info;
  302. PlanningHelpers::GetRelativeInfo(totalPaths, currState, car_info);
  303. for(unsigned int it=0; it< rollOuts.size(); it++)
  304. {
  305. int skip_id = -1;
  306. for(unsigned int icon = 0; icon < contourPoints.size(); icon++)
  307. {
  308. if(skip_id == contourPoints.at(icon).id)
  309. continue;
  310. RelativeInfo obj_info;
  311. PlanningHelpers::GetRelativeInfo(totalPaths, contourPoints.at(icon), obj_info);
  312. double longitudinalDist = PlanningHelpers::GetExactDistanceOnTrajectory(totalPaths, car_info, obj_info);
  313. if(obj_info.iFront == 0 && longitudinalDist > 0)
  314. longitudinalDist = -longitudinalDist;
  315. 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);
  316. if(contourPoints.at(icon).v < params.minSpeed && direct_distance > (m_LateralSkipDistance+contourPoints.at(icon).cost))
  317. {
  318. skip_id = contourPoints.at(icon).id;
  319. continue;
  320. }
  321. double close_in_percentage = 1;
  322. // close_in_percentage = ((longitudinalDist- critical_long_front_distance)/params.rollInMargin)*4.0;
  323. //
  324. // if(close_in_percentage <= 0 || close_in_percentage > 1) close_in_percentage = 1;
  325. double distance_from_center = trajectoryCosts.at(iCostIndex).distance_from_center;
  326. if(close_in_percentage < 1)
  327. distance_from_center = distance_from_center - distance_from_center * (1.0-close_in_percentage);
  328. double lateralDist = fabs(obj_info.perp_distance - distance_from_center);
  329. if(longitudinalDist < -carInfo.length || longitudinalDist > params.minFollowingDistance || lateralDist > m_LateralSkipDistance)
  330. {
  331. continue;
  332. }
  333. longitudinalDist = longitudinalDist - critical_long_front_distance;
  334. if(m_SafetyBorder.PointInsidePolygon(m_SafetyBorder, contourPoints.at(icon).pos) == true)
  335. trajectoryCosts.at(iCostIndex).bBlocked = true;
  336. if(lateralDist <= critical_lateral_distance
  337. && longitudinalDist >= -carInfo.length/1.5
  338. && longitudinalDist < params.minFollowingDistance)
  339. trajectoryCosts.at(iCostIndex).bBlocked = true;
  340. if(lateralDist != 0)
  341. trajectoryCosts.at(iCostIndex).lateral_cost += 1.0/lateralDist;
  342. if(longitudinalDist != 0)
  343. trajectoryCosts.at(iCostIndex).longitudinal_cost += 1.0/fabs(longitudinalDist);
  344. if(longitudinalDist >= -critical_long_front_distance && longitudinalDist < trajectoryCosts.at(iCostIndex).closest_obj_distance)
  345. {
  346. trajectoryCosts.at(iCostIndex).closest_obj_distance = longitudinalDist;
  347. trajectoryCosts.at(iCostIndex).closest_obj_velocity = contourPoints.at(icon).v;
  348. }
  349. }
  350. iCostIndex++;
  351. }
  352. }
  353. }
  354. void TrajectoryDynamicCosts::CalculateLateralAndLongitudinalCosts(vector<TrajectoryCost>& trajectoryCosts,
  355. const vector<vector<vector<WayPoint> > >& rollOuts, const vector<vector<WayPoint> >& totalPaths,
  356. const WayPoint& currState, const vector<WayPoint>& contourPoints, const PlanningParams& params,
  357. const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState)
  358. {
  359. double critical_lateral_distance = carInfo.width/2.0 + params.horizontalSafetyDistancel;
  360. double critical_long_front_distance = carInfo.wheel_base/2.0 + carInfo.length/2.0 + params.verticalSafetyDistance;
  361. double critical_long_back_distance = carInfo.length/2.0 + params.verticalSafetyDistance - carInfo.wheel_base/2.0;
  362. int iCostIndex = 0;
  363. PlannerHNS::Mat3 invRotationMat(currState.pos.a-M_PI_2);
  364. PlannerHNS::Mat3 invTranslationMat(currState.pos.x, currState.pos.y);
  365. double corner_slide_distance = critical_lateral_distance/2.0;
  366. double ratio_to_angle = corner_slide_distance/carInfo.max_steer_angle;
  367. double slide_distance = vehicleState.steer * ratio_to_angle;
  368. GPSPoint bottom_left(-critical_lateral_distance ,-critical_long_back_distance, currState.pos.z, 0);
  369. GPSPoint bottom_right(critical_lateral_distance, -critical_long_back_distance, currState.pos.z, 0);
  370. GPSPoint top_right_car(critical_lateral_distance, carInfo.wheel_base/3.0 + carInfo.length/3.0, currState.pos.z, 0);
  371. GPSPoint top_left_car(-critical_lateral_distance, carInfo.wheel_base/3.0 + carInfo.length/3.0, currState.pos.z, 0);
  372. GPSPoint top_right(critical_lateral_distance - slide_distance, critical_long_front_distance, currState.pos.z, 0);
  373. GPSPoint top_left(-critical_lateral_distance - slide_distance , critical_long_front_distance, currState.pos.z, 0);
  374. bottom_left = invRotationMat*bottom_left;
  375. bottom_left = invTranslationMat*bottom_left;
  376. top_right = invRotationMat*top_right;
  377. top_right = invTranslationMat*top_right;
  378. bottom_right = invRotationMat*bottom_right;
  379. bottom_right = invTranslationMat*bottom_right;
  380. top_left = invRotationMat*top_left;
  381. top_left = invTranslationMat*top_left;
  382. top_right_car = invRotationMat*top_right_car;
  383. top_right_car = invTranslationMat*top_right_car;
  384. top_left_car = invRotationMat*top_left_car;
  385. top_left_car = invTranslationMat*top_left_car;
  386. m_SafetyBorder.points.clear();
  387. m_SafetyBorder.points.push_back(bottom_left) ;
  388. m_SafetyBorder.points.push_back(bottom_right) ;
  389. m_SafetyBorder.points.push_back(top_right_car) ;
  390. m_SafetyBorder.points.push_back(top_right) ;
  391. m_SafetyBorder.points.push_back(top_left) ;
  392. m_SafetyBorder.points.push_back(top_left_car) ;
  393. for(unsigned int il=0; il < rollOuts.size(); il++)
  394. {
  395. if(rollOuts.at(il).size() > 0 && rollOuts.at(il).at(0).size()>0)
  396. {
  397. RelativeInfo car_info;
  398. PlanningHelpers::GetRelativeInfo(totalPaths.at(il), currState, car_info);
  399. for(unsigned int it=0; it< rollOuts.at(il).size(); it++)
  400. {
  401. int skip_id = -1;
  402. for(unsigned int icon = 0; icon < contourPoints.size(); icon++)
  403. {
  404. if(skip_id == contourPoints.at(icon).id)
  405. continue;
  406. RelativeInfo obj_info;
  407. PlanningHelpers::GetRelativeInfo(totalPaths.at(il), contourPoints.at(icon), obj_info);
  408. double longitudinalDist = PlanningHelpers::GetExactDistanceOnTrajectory(totalPaths.at(il), car_info, obj_info);
  409. if(obj_info.iFront == 0 && longitudinalDist > 0)
  410. longitudinalDist = -longitudinalDist;
  411. 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);
  412. if(contourPoints.at(icon).v < params.minSpeed && direct_distance > (m_LateralSkipDistance+contourPoints.at(icon).cost))
  413. {
  414. skip_id = contourPoints.at(icon).id;
  415. continue;
  416. }
  417. double close_in_percentage = 1;
  418. // close_in_percentage = ((longitudinalDist- critical_long_front_distance)/params.rollInMargin)*4.0;
  419. //
  420. // if(close_in_percentage <= 0 || close_in_percentage > 1) close_in_percentage = 1;
  421. double distance_from_center = trajectoryCosts.at(iCostIndex).distance_from_center;
  422. if(close_in_percentage < 1)
  423. distance_from_center = distance_from_center - distance_from_center * (1.0-close_in_percentage);
  424. double lateralDist = fabs(obj_info.perp_distance - distance_from_center);
  425. if(longitudinalDist < -carInfo.length || longitudinalDist > params.minFollowingDistance || lateralDist > m_LateralSkipDistance)
  426. {
  427. continue;
  428. }
  429. longitudinalDist = longitudinalDist - critical_long_front_distance;
  430. if(m_SafetyBorder.PointInsidePolygon(m_SafetyBorder, contourPoints.at(icon).pos) == true)
  431. trajectoryCosts.at(iCostIndex).bBlocked = true;
  432. if(lateralDist <= critical_lateral_distance
  433. && longitudinalDist >= -carInfo.length/1.5
  434. && longitudinalDist < params.minFollowingDistance)
  435. trajectoryCosts.at(iCostIndex).bBlocked = true;
  436. if(lateralDist != 0)
  437. trajectoryCosts.at(iCostIndex).lateral_cost += 1.0/lateralDist;
  438. if(longitudinalDist != 0)
  439. trajectoryCosts.at(iCostIndex).longitudinal_cost += 1.0/fabs(longitudinalDist);
  440. if(longitudinalDist >= -critical_long_front_distance && longitudinalDist < trajectoryCosts.at(iCostIndex).closest_obj_distance)
  441. {
  442. trajectoryCosts.at(iCostIndex).closest_obj_distance = longitudinalDist;
  443. trajectoryCosts.at(iCostIndex).closest_obj_velocity = contourPoints.at(icon).v;
  444. }
  445. }
  446. iCostIndex++;
  447. }
  448. }
  449. }
  450. }
  451. void TrajectoryDynamicCosts::NormalizeCosts(vector<TrajectoryCost>& trajectoryCosts)
  452. {
  453. //Normalize costs
  454. double totalPriorities = 0;
  455. double totalChange = 0;
  456. double totalLateralCosts = 0;
  457. double totalLongitudinalCosts = 0;
  458. double transitionCosts = 0;
  459. for(unsigned int ic = 0; ic< trajectoryCosts.size(); ic++)
  460. {
  461. totalPriorities += trajectoryCosts.at(ic).priority_cost;
  462. transitionCosts += trajectoryCosts.at(ic).transition_cost;
  463. }
  464. for(unsigned int ic = 0; ic< trajectoryCosts.size(); ic++)
  465. {
  466. totalChange += trajectoryCosts.at(ic).lane_change_cost;
  467. totalLateralCosts += trajectoryCosts.at(ic).lateral_cost;
  468. totalLongitudinalCosts += trajectoryCosts.at(ic).longitudinal_cost;
  469. }
  470. // cout << "------ Normalizing Step " << endl;
  471. for(unsigned int ic = 0; ic< trajectoryCosts.size(); ic++)
  472. {
  473. if(totalPriorities != 0)
  474. trajectoryCosts.at(ic).priority_cost = trajectoryCosts.at(ic).priority_cost / totalPriorities;
  475. else
  476. trajectoryCosts.at(ic).priority_cost = 0;
  477. if(transitionCosts != 0)
  478. trajectoryCosts.at(ic).transition_cost = trajectoryCosts.at(ic).transition_cost / transitionCosts;
  479. else
  480. trajectoryCosts.at(ic).transition_cost = 0;
  481. if(totalChange != 0)
  482. trajectoryCosts.at(ic).lane_change_cost = trajectoryCosts.at(ic).lane_change_cost / totalChange;
  483. else
  484. trajectoryCosts.at(ic).lane_change_cost = 0;
  485. if(totalLateralCosts != 0)
  486. trajectoryCosts.at(ic).lateral_cost = trajectoryCosts.at(ic).lateral_cost / totalLateralCosts;
  487. else
  488. trajectoryCosts.at(ic).lateral_cost = 0;
  489. if(totalLongitudinalCosts != 0)
  490. trajectoryCosts.at(ic).longitudinal_cost = trajectoryCosts.at(ic).longitudinal_cost / totalLongitudinalCosts;
  491. else
  492. trajectoryCosts.at(ic).longitudinal_cost = 0;
  493. trajectoryCosts.at(ic).cost = (m_WeightPriority*trajectoryCosts.at(ic).priority_cost + m_WeightTransition*trajectoryCosts.at(ic).transition_cost + m_WeightLat*trajectoryCosts.at(ic).lateral_cost + m_WeightLong*trajectoryCosts.at(ic).longitudinal_cost)/4.0;
  494. // cout << "Index: " << ic
  495. // << ", Priority: " << trajectoryCosts.at(ic).priority_cost
  496. // << ", Transition: " << trajectoryCosts.at(ic).transition_cost
  497. // << ", Lat: " << trajectoryCosts.at(ic).lateral_cost
  498. // << ", Long: " << trajectoryCosts.at(ic).longitudinal_cost
  499. // << ", Change: " << trajectoryCosts.at(ic).lane_change_cost
  500. // << ", Avg: " << trajectoryCosts.at(ic).cost
  501. // << endl;
  502. }
  503. // cout << "------------------------ " << endl;
  504. }
  505. vector<TrajectoryCost> TrajectoryDynamicCosts::CalculatePriorityAndLaneChangeCosts(const vector<vector<WayPoint> >& laneRollOuts,
  506. const int& lane_index, const PlanningParams& params)
  507. {
  508. vector<TrajectoryCost> costs;
  509. TrajectoryCost tc;
  510. int centralIndex = params.rollOutNumber/2;
  511. tc.lane_index = lane_index;
  512. for(unsigned int it=0; it< laneRollOuts.size(); it++)
  513. {
  514. tc.index = it;
  515. tc.relative_index = it - centralIndex;
  516. tc.distance_from_center = params.rollOutDensity*tc.relative_index;
  517. tc.priority_cost = fabs(tc.distance_from_center);
  518. tc.closest_obj_distance = params.horizonDistance;
  519. tc.lane_change_cost = laneRollOuts.at(it).at(0).laneChangeCost;
  520. // if(laneRollOuts.at(it).at(0).bDir == FORWARD_LEFT_DIR || laneRollOuts.at(it).at(0).bDir == FORWARD_RIGHT_DIR)
  521. // tc.lane_change_cost = 1;
  522. // 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)
  523. // tc.lane_change_cost = 2;
  524. // else
  525. // tc.lane_change_cost = 0;
  526. costs.push_back(tc);
  527. }
  528. return costs;
  529. }
  530. void TrajectoryDynamicCosts::CalculateTransitionCosts(vector<TrajectoryCost>& trajectoryCosts, const int& currTrajectoryIndex, const PlanningParams& params)
  531. {
  532. for(int ic = 0; ic< trajectoryCosts.size(); ic++)
  533. {
  534. trajectoryCosts.at(ic).transition_cost = fabs(params.rollOutDensity * (ic - currTrajectoryIndex));
  535. }
  536. }
  537. /**
  538. * @brief Validate input, each trajectory must have at least 1 way point
  539. * @param rollOuts
  540. * @return true if data isvalid for cost calculation
  541. */
  542. bool TrajectoryDynamicCosts::ValidateRollOutsInput(const vector<vector<vector<WayPoint> > >& rollOuts)
  543. {
  544. if(rollOuts.size()==0)
  545. return false;
  546. for(unsigned int il = 0; il < rollOuts.size(); il++)
  547. {
  548. if(rollOuts.at(il).size() == 0)
  549. return false;
  550. }
  551. return true;
  552. }
  553. void TrajectoryDynamicCosts::CalculateIntersectionVelocities(const std::vector<PlannerHNS::WayPoint>& path, const PlannerHNS::DetectedObject& obj, const WayPoint& currPose, const CAR_BASIC_INFO& carInfo, const double& c_lateral_d, WayPoint& collisionPoint, TrajectoryCost& trajectoryCosts)
  554. {
  555. trajectoryCosts.bBlocked = false;
  556. int closest_path_i = path.size();
  557. for(unsigned int k = 0; k < obj.predTrajectories.size(); k++)
  558. {
  559. for(unsigned int j = 0; j < obj.predTrajectories.at(k).size(); j++)
  560. {
  561. for(unsigned int i = 0; i < path.size(); i++)
  562. {
  563. //if(path.at(i).timeCost > -1)
  564. {
  565. double collision_distance = hypot(path.at(i).pos.x-obj.predTrajectories.at(k).at(j).pos.x, path.at(i).pos.y-obj.predTrajectories.at(k).at(j).pos.y);
  566. double collision_t = fabs(path.at(i).timeCost - obj.predTrajectories.at(k).at(j).timeCost);
  567. //if(collision_distance <= c_lateral_d && i < closest_path_i && collision_t < m_CollisionTimeDiff)
  568. if(collision_distance <= c_lateral_d && i < closest_path_i)
  569. {
  570. closest_path_i = i;
  571. double a = UtilityHNS::UtilityH::AngleBetweenTwoAnglesPositive(path.at(i).pos.a, obj.predTrajectories.at(k).at(j).pos.a)/M_PI;
  572. if(a < 0.25 && (currPose.v - obj.center.v) > 0)
  573. trajectoryCosts.closest_obj_velocity = (currPose.v - obj.center.v);
  574. else
  575. trajectoryCosts.closest_obj_velocity = currPose.v;
  576. collisionPoint = path.at(i);
  577. collisionPoint.collisionCost = collision_t;
  578. collisionPoint.cost = collision_distance;
  579. trajectoryCosts.bBlocked = true;
  580. }
  581. }
  582. }
  583. }
  584. }
  585. }
  586. int TrajectoryDynamicCosts::GetCurrentRollOutIndex(const std::vector<WayPoint>& path, const WayPoint& currState, const PlanningParams& params)
  587. {
  588. RelativeInfo obj_info;
  589. PlanningHelpers::GetRelativeInfo(path, currState, obj_info);
  590. int currIndex = params.rollOutNumber/2 + floor(obj_info.perp_distance/params.rollOutDensity);
  591. if(currIndex < 0)
  592. currIndex = 0;
  593. else if(currIndex > params.rollOutNumber)
  594. currIndex = params.rollOutNumber;
  595. return currIndex;
  596. }
  597. void TrajectoryDynamicCosts::InitializeCosts(const vector<vector<WayPoint> >& rollOuts, const PlanningParams& params)
  598. {
  599. m_TrajectoryCosts.clear();
  600. if(rollOuts.size()>0)
  601. {
  602. TrajectoryCost tc;
  603. int centralIndex = params.rollOutNumber/2;
  604. tc.lane_index = 0;
  605. for(unsigned int it=0; it< rollOuts.size(); it++)
  606. {
  607. tc.index = it;
  608. tc.relative_index = it - centralIndex;
  609. tc.distance_from_center = params.rollOutDensity*tc.relative_index;
  610. tc.priority_cost = fabs(tc.distance_from_center);
  611. tc.closest_obj_distance = params.horizonDistance;
  612. if(rollOuts.at(it).size() > 0)
  613. tc.lane_change_cost = rollOuts.at(it).at(0).laneChangeCost;
  614. m_TrajectoryCosts.push_back(tc);
  615. }
  616. }
  617. }
  618. void TrajectoryDynamicCosts::InitializeSafetyPolygon(const WayPoint& currState, const CAR_BASIC_INFO& carInfo, const VehicleState& vehicleState, const double& c_lateral_d, const double& c_long_front_d, const double& c_long_back_d)
  619. {
  620. PlannerHNS::Mat3 invRotationMat(currState.pos.a-M_PI_2);
  621. PlannerHNS::Mat3 invTranslationMat(currState.pos.x, currState.pos.y);
  622. double corner_slide_distance = c_lateral_d/2.0;
  623. double ratio_to_angle = corner_slide_distance/carInfo.max_steer_angle;
  624. double slide_distance = vehicleState.steer * ratio_to_angle;
  625. GPSPoint bottom_left(-c_lateral_d ,-c_long_back_d, currState.pos.z, 0);
  626. GPSPoint bottom_right(c_lateral_d, -c_long_back_d, currState.pos.z, 0);
  627. GPSPoint top_right_car(c_lateral_d, carInfo.wheel_base/3.0 + carInfo.length/3.0, currState.pos.z, 0);
  628. GPSPoint top_left_car(-c_lateral_d, carInfo.wheel_base/3.0 + carInfo.length/3.0, currState.pos.z, 0);
  629. GPSPoint top_right(c_lateral_d - slide_distance, c_long_front_d, currState.pos.z, 0);
  630. GPSPoint top_left(-c_lateral_d - slide_distance , c_long_front_d, currState.pos.z, 0);
  631. bottom_left = invRotationMat*bottom_left;
  632. bottom_left = invTranslationMat*bottom_left;
  633. top_right = invRotationMat*top_right;
  634. top_right = invTranslationMat*top_right;
  635. bottom_right = invRotationMat*bottom_right;
  636. bottom_right = invTranslationMat*bottom_right;
  637. top_left = invRotationMat*top_left;
  638. top_left = invTranslationMat*top_left;
  639. top_right_car = invRotationMat*top_right_car;
  640. top_right_car = invTranslationMat*top_right_car;
  641. top_left_car = invRotationMat*top_left_car;
  642. top_left_car = invTranslationMat*top_left_car;
  643. m_SafetyBorder.points.clear();
  644. m_SafetyBorder.points.push_back(bottom_left) ;
  645. m_SafetyBorder.points.push_back(bottom_right) ;
  646. m_SafetyBorder.points.push_back(top_right_car) ;
  647. m_SafetyBorder.points.push_back(top_right) ;
  648. m_SafetyBorder.points.push_back(top_left) ;
  649. m_SafetyBorder.points.push_back(top_left_car) ;
  650. }
  651. void TrajectoryDynamicCosts::CalculateLateralAndLongitudinalCostsDynamic(const std::vector<PlannerHNS::DetectedObject>& obj_list, const vector<vector<WayPoint> >& rollOuts, const vector<WayPoint>& totalPaths,
  652. const WayPoint& currState, const PlanningParams& params, const CAR_BASIC_INFO& carInfo,
  653. const VehicleState& vehicleState, const double& c_lateral_d, const double& c_long_front_d, const double& c_long_back_d )
  654. {
  655. RelativeInfo car_info;
  656. PlanningHelpers::GetRelativeInfo(totalPaths, currState, car_info);
  657. m_CollisionPoints.clear();
  658. for(unsigned int i=0; i < obj_list.size(); i++)
  659. {
  660. if(obj_list.at(i).label.compare("curb") == 0)
  661. {
  662. double d = hypot(obj_list.at(i).center.pos.y - currState.pos.y , obj_list.at(i).center.pos.x - currState.pos.x);
  663. if(d > params.minFollowingDistance + c_lateral_d)
  664. continue;
  665. }
  666. if(obj_list.at(i).bVelocity && obj_list.at(i).predTrajectories.size() > 0) // dynamic
  667. {
  668. for(unsigned int ir=0; ir < rollOuts.size(); ir++)
  669. {
  670. WayPoint collisionPoint;
  671. TrajectoryCost trajectoryCosts;
  672. CalculateIntersectionVelocities(rollOuts.at(ir), obj_list.at(i), currState, carInfo, c_lateral_d, collisionPoint,trajectoryCosts);
  673. if(trajectoryCosts.bBlocked)
  674. {
  675. RelativeInfo col_info;
  676. PlanningHelpers::GetRelativeInfo(totalPaths, collisionPoint, col_info);
  677. double longitudinalDist = PlanningHelpers::GetExactDistanceOnTrajectory(totalPaths, car_info, col_info);
  678. if(col_info.iFront == 0 && longitudinalDist > 0)
  679. longitudinalDist = -longitudinalDist;
  680. if(longitudinalDist < -carInfo.length || longitudinalDist > params.minFollowingDistance || fabs(longitudinalDist) < carInfo.width/2.0)
  681. continue;
  682. //std::cout << "LongDistance: " << longitudinalDist << std::endl;
  683. if(longitudinalDist >= -c_long_front_d && longitudinalDist < m_TrajectoryCosts.at(ir).closest_obj_distance)
  684. m_TrajectoryCosts.at(ir).closest_obj_distance = longitudinalDist;
  685. m_TrajectoryCosts.at(ir).closest_obj_velocity = trajectoryCosts.closest_obj_velocity;
  686. m_TrajectoryCosts.at(ir).bBlocked = true;
  687. m_CollisionPoints.push_back(collisionPoint);
  688. }
  689. }
  690. }
  691. else
  692. {
  693. RelativeInfo obj_info;
  694. WayPoint corner_p;
  695. for(unsigned int icon = 0; icon < obj_list.at(i).contour.size(); icon++)
  696. {
  697. if(m_SafetyBorder.PointInsidePolygon(m_SafetyBorder, obj_list.at(i).contour.at(icon)) == true)
  698. {
  699. for(unsigned int it=0; it< rollOuts.size(); it++)
  700. m_TrajectoryCosts.at(it).bBlocked = true;
  701. return;
  702. }
  703. corner_p.pos = obj_list.at(i).contour.at(icon);
  704. PlanningHelpers::GetRelativeInfo(totalPaths, corner_p, obj_info);
  705. double longitudinalDist = PlanningHelpers::GetExactDistanceOnTrajectory(totalPaths, car_info, obj_info);
  706. if(obj_info.iFront == 0 && longitudinalDist > 0)
  707. longitudinalDist = -longitudinalDist;
  708. if(longitudinalDist < -carInfo.length || longitudinalDist > params.minFollowingDistance)
  709. continue;
  710. longitudinalDist = longitudinalDist - c_long_front_d;
  711. for(unsigned int it=0; it< rollOuts.size(); it++)
  712. {
  713. double lateralDist = fabs(obj_info.perp_distance - m_TrajectoryCosts.at(it).distance_from_center);
  714. if(lateralDist > m_LateralSkipDistance)
  715. continue;
  716. if(lateralDist <= c_lateral_d && longitudinalDist > -carInfo.length && longitudinalDist < params.minFollowingDistance)
  717. {
  718. m_TrajectoryCosts.at(it).bBlocked = true;
  719. m_CollisionPoints.push_back(obj_info.perp_point);
  720. }
  721. if(lateralDist != 0)
  722. m_TrajectoryCosts.at(it).lateral_cost += 1.0/lateralDist;
  723. if(longitudinalDist != 0)
  724. m_TrajectoryCosts.at(it).longitudinal_cost += 1.0/fabs(longitudinalDist);
  725. if(longitudinalDist >= -c_long_front_d && longitudinalDist < m_TrajectoryCosts.at(it).closest_obj_distance)
  726. {
  727. m_TrajectoryCosts.at(it).closest_obj_distance = longitudinalDist;
  728. m_TrajectoryCosts.at(it).closest_obj_velocity = obj_list.at(i).center.v;
  729. }
  730. }
  731. }
  732. }
  733. }
  734. }
  735. }