DecisionMaker.cpp 18 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489
  1. /// \file DecisionMaker.cpp
  2. /// \brief Initialize behaviors state machine, and calculate required parameters for the state machine transition conditions
  3. /// \author Hatem Darweesh
  4. /// \date Dec 14, 2016
  5. #include "op_planner/DecisionMaker.h"
  6. #include "op_utility/UtilityH.h"
  7. #include "op_planner/PlanningHelpers.h"
  8. #include "op_planner/MappingHelpers.h"
  9. #include "op_planner/MatrixOperations.h"
  10. namespace PlannerHNS
  11. {
  12. DecisionMaker::DecisionMaker()
  13. {
  14. m_iCurrentTotalPathId = 0;
  15. pLane = 0;
  16. m_pCurrentBehaviorState = 0;
  17. m_pGoToGoalState = 0;
  18. m_pStopState= 0;
  19. m_pWaitState= 0;
  20. m_pMissionCompleteState= 0;
  21. m_pAvoidObstacleState = 0;
  22. m_pTrafficLightStopState = 0;
  23. m_pTrafficLightWaitState = 0;
  24. m_pStopSignStopState = 0;
  25. m_pStopSignWaitState = 0;
  26. m_pFollowState = 0;
  27. m_MaxLaneSearchDistance = 3.0;
  28. m_pStopState = 0;
  29. m_pMissionCompleteState = 0;
  30. m_pGoalState = 0;
  31. m_pGoToGoalState = 0;
  32. m_pWaitState = 0;
  33. m_pInitState = 0;
  34. m_pFollowState = 0;
  35. m_pAvoidObstacleState = 0;
  36. }
  37. DecisionMaker::~DecisionMaker()
  38. {
  39. delete m_pStopState;
  40. delete m_pMissionCompleteState;
  41. delete m_pGoalState;
  42. delete m_pGoToGoalState;
  43. delete m_pWaitState;
  44. delete m_pInitState;
  45. delete m_pFollowState;
  46. delete m_pAvoidObstacleState;
  47. delete m_pTrafficLightStopState;
  48. delete m_pTrafficLightWaitState;
  49. delete m_pStopSignWaitState;
  50. delete m_pStopSignStopState;
  51. }
  52. void DecisionMaker::Init(const ControllerParams& ctrlParams, const PlannerHNS::PlanningParams& params,const CAR_BASIC_INFO& carInfo)
  53. {
  54. m_CarInfo = carInfo;
  55. m_ControlParams = ctrlParams;
  56. m_params = params;
  57. m_pidVelocity.Init(0.01, 0.004, 0.01);
  58. m_pidVelocity.Setlimit(m_params.maxSpeed, 0);
  59. m_pidStopping.Init(0.05, 0.05, 0.1);
  60. m_pidStopping.Setlimit(m_params.horizonDistance, 0);
  61. m_pidFollowing.Init(0.05, 0.05, 0.01);
  62. m_pidFollowing.Setlimit(m_params.minFollowingDistance, 0);
  63. InitBehaviorStates();
  64. if(m_pCurrentBehaviorState)
  65. m_pCurrentBehaviorState->SetBehaviorsParams(&m_params);
  66. }
  67. void DecisionMaker::InitBehaviorStates()
  68. {
  69. m_pStopState = new StopState(&m_params, 0, 0);
  70. m_pMissionCompleteState = new MissionAccomplishedStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), 0);
  71. m_pGoalState = new GoalStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pMissionCompleteState);
  72. m_pGoToGoalState = new ForwardStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoalState);
  73. m_pInitState = new InitStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState);
  74. m_pFollowState = new FollowStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState);
  75. m_pAvoidObstacleState = new SwerveStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState);
  76. m_pStopSignWaitState = new StopSignWaitStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState);
  77. m_pStopSignStopState = new StopSignStopStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pStopSignWaitState);
  78. m_pTrafficLightWaitState = new TrafficLightWaitStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState);
  79. m_pTrafficLightStopState = new TrafficLightStopStateII(m_pStopState->m_pParams, m_pStopState->GetCalcParams(), m_pGoToGoalState);
  80. m_pGoToGoalState->InsertNextState(m_pAvoidObstacleState);
  81. m_pGoToGoalState->InsertNextState(m_pStopSignStopState);
  82. m_pGoToGoalState->InsertNextState(m_pTrafficLightStopState);
  83. m_pGoToGoalState->InsertNextState(m_pFollowState);
  84. m_pGoToGoalState->decisionMakingCount = 0;//m_params.nReliableCount;
  85. m_pGoalState->InsertNextState(m_pGoToGoalState);
  86. m_pStopSignWaitState->decisionMakingTime = m_params.stopSignStopTime;
  87. m_pStopSignWaitState->InsertNextState(m_pStopSignStopState);
  88. m_pStopSignWaitState->InsertNextState(m_pGoalState);
  89. m_pTrafficLightStopState->InsertNextState(m_pTrafficLightWaitState);
  90. m_pTrafficLightWaitState->InsertNextState(m_pTrafficLightStopState);
  91. m_pTrafficLightWaitState->InsertNextState(m_pGoalState);
  92. m_pFollowState->InsertNextState(m_pAvoidObstacleState);
  93. m_pFollowState->InsertNextState(m_pStopSignStopState);
  94. m_pFollowState->InsertNextState(m_pTrafficLightStopState);
  95. m_pFollowState->InsertNextState(m_pGoalState);
  96. m_pFollowState->decisionMakingCount = 0;//m_params.nReliableCount;
  97. m_pInitState->decisionMakingCount = 0;//m_params.nReliableCount;
  98. m_pCurrentBehaviorState = m_pInitState;
  99. }
  100. bool DecisionMaker::GetNextTrafficLight(const int& prevTrafficLightId, const std::vector<PlannerHNS::TrafficLight>& trafficLights, PlannerHNS::TrafficLight& trafficL)
  101. {
  102. for(unsigned int i = 0; i < trafficLights.size(); i++)
  103. {
  104. double d = hypot(trafficLights.at(i).pos.y - state.pos.y, trafficLights.at(i).pos.x - state.pos.x);
  105. if(d <= trafficLights.at(i).stoppingDistance)
  106. {
  107. double a_diff = UtilityHNS::UtilityH::AngleBetweenTwoAnglesPositive(UtilityHNS::UtilityH::FixNegativeAngle(trafficLights.at(i).pos.a) , UtilityHNS::UtilityH::FixNegativeAngle(state.pos.a));
  108. if(a_diff < M_PI_2 && trafficLights.at(i).id != prevTrafficLightId)
  109. {
  110. //std::cout << "Detected Light, ID = " << trafficLights.at(i).id << ", Distance = " << d << ", Angle = " << trafficLights.at(i).pos.a*RAD2DEG << ", Car Heading = " << state.pos.a*RAD2DEG << ", Diff = " << a_diff*RAD2DEG << std::endl;
  111. trafficL = trafficLights.at(i);
  112. return true;
  113. }
  114. }
  115. }
  116. return false;
  117. }
  118. void DecisionMaker::CalculateImportantParameterForDecisionMaking(const PlannerHNS::VehicleState& car_state,
  119. const int& goalID, const bool& bEmergencyStop, const std::vector<TrafficLight>& detectedLights,
  120. const TrajectoryCost& bestTrajectory)
  121. {
  122. if(m_TotalPath.size() == 0) return;
  123. PreCalculatedConditions* pValues = m_pCurrentBehaviorState->GetCalcParams();
  124. if(m_CarInfo.max_deceleration != 0)
  125. pValues->minStoppingDistance = -pow(car_state.speed, 2)/(m_CarInfo.max_deceleration);
  126. pValues->iCentralTrajectory = m_pCurrentBehaviorState->m_pParams->rollOutNumber/2;
  127. if(pValues->iPrevSafeTrajectory < 0)
  128. pValues->iPrevSafeTrajectory = pValues->iCentralTrajectory;
  129. pValues->stoppingDistances.clear();
  130. pValues->currentVelocity = car_state.speed;
  131. pValues->bTrafficIsRed = false;
  132. pValues->currentTrafficLightID = -1;
  133. pValues->bFullyBlock = false;
  134. pValues->distanceToNext = bestTrajectory.closest_obj_distance;
  135. pValues->velocityOfNext = bestTrajectory.closest_obj_velocity;
  136. if(bestTrajectory.index >=0 && bestTrajectory.index < (int)m_RollOuts.size())
  137. pValues->iCurrSafeTrajectory = bestTrajectory.index;
  138. else
  139. pValues->iCurrSafeTrajectory = pValues->iCentralTrajectory;
  140. pValues->bFullyBlock = bestTrajectory.bBlocked;
  141. if(bestTrajectory.lane_index >=0)
  142. pValues->iCurrSafeLane = bestTrajectory.lane_index;
  143. else
  144. {
  145. PlannerHNS::RelativeInfo info;
  146. PlannerHNS::PlanningHelpers::GetRelativeInfoRange(m_TotalPath, state, m_params.rollOutDensity*m_params.rollOutNumber/2.0 + 0.1, info);
  147. pValues->iCurrSafeLane = info.iGlobalPath;
  148. }
  149. double critical_long_front_distance = m_CarInfo.wheel_base/2.0 + m_CarInfo.length/2.0 + m_params.verticalSafetyDistance;
  150. if(ReachEndOfGlobalPath(pValues->minStoppingDistance + critical_long_front_distance, pValues->iCurrSafeLane))
  151. pValues->currentGoalID = -1;
  152. else
  153. pValues->currentGoalID = goalID;
  154. m_iCurrentTotalPathId = pValues->iCurrSafeLane;
  155. int stopLineID = -1;
  156. int stopSignID = -1;
  157. int trafficLightID = -1;
  158. double distanceToClosestStopLine = 0;
  159. bool bGreenTrafficLight = true;
  160. distanceToClosestStopLine = PlanningHelpers::GetDistanceToClosestStopLineAndCheck(m_TotalPath.at(pValues->iCurrSafeLane), state, m_params.giveUpDistance, stopLineID, stopSignID, trafficLightID) - critical_long_front_distance;
  161. //std::cout << "StopLineID" << stopLineID << ", StopSignID: " << stopSignID << ", TrafficLightID: " << trafficLightID << ", Distance: " << distanceToClosestStopLine << ", MinStopDistance: " << pValues->minStoppingDistance << std::endl;
  162. if(distanceToClosestStopLine > m_params.giveUpDistance && distanceToClosestStopLine < (pValues->minStoppingDistance + 1.0))
  163. {
  164. if(m_pCurrentBehaviorState->m_pParams->enableTrafficLightBehavior)
  165. {
  166. pValues->currentTrafficLightID = trafficLightID;
  167. //std::cout << "Detected Traffic Light: " << trafficLightID << std::endl;
  168. for(unsigned int i=0; i< detectedLights.size(); i++)
  169. {
  170. if(detectedLights.at(i).id == trafficLightID)
  171. bGreenTrafficLight = (detectedLights.at(i).lightState == GREEN_LIGHT);
  172. }
  173. }
  174. if(m_pCurrentBehaviorState->m_pParams->enableStopSignBehavior)
  175. pValues->currentStopSignID = stopSignID;
  176. pValues->stoppingDistances.push_back(distanceToClosestStopLine);
  177. //std::cout << "LP => D: " << pValues->distanceToStop() << ", PrevSignID: " << pValues->prevTrafficLightID << ", CurrSignID: " << pValues->currentTrafficLightID << ", Green: " << bGreenTrafficLight << endl;
  178. }
  179. //std::cout << "Distance To Closest: " << distanceToClosestStopLine << ", Stop LineID: " << stopLineID << ", Stop SignID: " << stopSignID << ", TFID: " << trafficLightID << std::endl;
  180. pValues->bTrafficIsRed = !bGreenTrafficLight;
  181. if(bEmergencyStop)
  182. {
  183. pValues->bFullyBlock = true;
  184. pValues->distanceToNext = 1;
  185. pValues->velocityOfNext = 0;
  186. }
  187. //cout << "Distances: " << pValues->stoppingDistances.size() << ", Distance To Stop : " << pValues->distanceToStop << endl;
  188. }
  189. void DecisionMaker::UpdateCurrentLane(const double& search_distance)
  190. {
  191. PlannerHNS::Lane* pMapLane = 0;
  192. PlannerHNS::Lane* pPathLane = 0;
  193. pPathLane = MappingHelpers::GetLaneFromPath(state, m_TotalPath.at(m_iCurrentTotalPathId));
  194. if(!pPathLane)
  195. {
  196. std::cout << "Performance Alert: Can't Find Lane Information in Global Path, Searching the Map :( " << std::endl;
  197. pMapLane = MappingHelpers::GetClosestLaneFromMap(state, m_Map, search_distance);
  198. }
  199. if(pPathLane)
  200. pLane = pPathLane;
  201. else if(pMapLane)
  202. pLane = pMapLane;
  203. else
  204. pLane = 0;
  205. }
  206. bool DecisionMaker::ReachEndOfGlobalPath(const double& min_distance, const int& iGlobalPathIndex)
  207. {
  208. if(m_TotalPath.size()==0) return false;
  209. PlannerHNS::RelativeInfo info;
  210. PlanningHelpers::GetRelativeInfo(m_TotalPath.at(iGlobalPathIndex), state, info);
  211. double d = 0;
  212. for(unsigned int i = info.iFront; i < m_TotalPath.at(iGlobalPathIndex).size()-1; i++)
  213. {
  214. d+= hypot(m_TotalPath.at(iGlobalPathIndex).at(i+1).pos.y - m_TotalPath.at(iGlobalPathIndex).at(i).pos.y, m_TotalPath.at(iGlobalPathIndex).at(i+1).pos.x - m_TotalPath.at(iGlobalPathIndex).at(i).pos.x);
  215. if(d > min_distance)
  216. return false;
  217. }
  218. return true;
  219. }
  220. void DecisionMaker::SetNewGlobalPath(const std::vector<std::vector<WayPoint> >& globalPath)
  221. {
  222. if(m_pCurrentBehaviorState)
  223. {
  224. m_pCurrentBehaviorState->GetCalcParams()->bNewGlobalPath = true;
  225. m_TotalOriginalPath = globalPath;
  226. }
  227. }
  228. bool DecisionMaker::SelectSafeTrajectory()
  229. {
  230. bool bNewTrajectory = false;
  231. PlannerHNS::PreCalculatedConditions *preCalcPrams = m_pCurrentBehaviorState->GetCalcParams();
  232. if(!preCalcPrams || m_RollOuts.size() == 0) return bNewTrajectory;
  233. int currIndex = PlannerHNS::PlanningHelpers::GetClosestNextPointIndexFast(m_Path, state);
  234. int index_limit = 0;
  235. if(index_limit<=0)
  236. index_limit = m_Path.size()/2.0;
  237. if(currIndex > index_limit
  238. || preCalcPrams->bRePlan
  239. || preCalcPrams->bNewGlobalPath)
  240. {
  241. std::cout << "New Local Plan !! " << currIndex << ", "<< preCalcPrams->bRePlan << ", " << preCalcPrams->bNewGlobalPath << ", " << m_TotalOriginalPath.at(0).size() << ", PrevLocal: " << m_Path.size();
  242. m_Path = m_RollOuts.at(preCalcPrams->iCurrSafeTrajectory);
  243. std::cout << ", NewLocal: " << m_Path.size() << std::endl;
  244. preCalcPrams->bNewGlobalPath = false;
  245. preCalcPrams->bRePlan = false;
  246. bNewTrajectory = true;
  247. }
  248. return bNewTrajectory;
  249. }
  250. PlannerHNS::BehaviorState DecisionMaker::GenerateBehaviorState(const PlannerHNS::VehicleState& vehicleState)
  251. {
  252. PlannerHNS::PreCalculatedConditions *preCalcPrams = m_pCurrentBehaviorState->GetCalcParams();
  253. m_pCurrentBehaviorState = m_pCurrentBehaviorState->GetNextState();
  254. if(m_pCurrentBehaviorState==0)
  255. m_pCurrentBehaviorState = m_pInitState;
  256. PlannerHNS::BehaviorState currentBehavior;
  257. currentBehavior.state = m_pCurrentBehaviorState->m_Behavior;
  258. currentBehavior.followDistance = preCalcPrams->distanceToNext;
  259. currentBehavior.minVelocity = 0;
  260. currentBehavior.stopDistance = preCalcPrams->distanceToStop();
  261. currentBehavior.followVelocity = preCalcPrams->velocityOfNext;
  262. if(preCalcPrams->iPrevSafeTrajectory<0 || preCalcPrams->iPrevSafeTrajectory >= m_RollOuts.size())
  263. currentBehavior.iTrajectory = preCalcPrams->iCurrSafeTrajectory;
  264. else
  265. currentBehavior.iTrajectory = preCalcPrams->iPrevSafeTrajectory;
  266. double average_braking_distance = -pow(vehicleState.speed, 2)/(m_CarInfo.max_deceleration) + m_params.additionalBrakingDistance;
  267. if(average_braking_distance < m_params.minIndicationDistance)
  268. average_braking_distance = m_params.minIndicationDistance;
  269. currentBehavior.indicator = PlanningHelpers::GetIndicatorsFromPath(m_Path, state, average_braking_distance );
  270. return currentBehavior;
  271. }
  272. double DecisionMaker::UpdateVelocityDirectlyToTrajectory(const BehaviorState& beh, const VehicleState& CurrStatus, const double& dt)
  273. {
  274. if(m_TotalOriginalPath.size() ==0 ) return 0;
  275. RelativeInfo info, total_info;
  276. PlanningHelpers::GetRelativeInfo(m_TotalOriginalPath.at(m_iCurrentTotalPathId), state, total_info);
  277. PlanningHelpers::GetRelativeInfo(m_Path, state, info);
  278. double average_braking_distance = -pow(CurrStatus.speed, 2)/(m_CarInfo.max_deceleration) + m_params.additionalBrakingDistance;
  279. double max_velocity = PlannerHNS::PlanningHelpers::GetVelocityAhead(m_TotalOriginalPath.at(m_iCurrentTotalPathId), total_info, total_info.iBack, average_braking_distance);
  280. unsigned int point_index = 0;
  281. double critical_long_front_distance = m_CarInfo.length/2.0;
  282. if(beh.state == TRAFFIC_LIGHT_STOP_STATE || beh.state == STOP_SIGN_STOP_STATE)
  283. {
  284. PlanningHelpers::GetFollowPointOnTrajectory(m_Path, info, beh.stopDistance - critical_long_front_distance, point_index);
  285. double e = -beh.stopDistance;
  286. double desiredVelocity = m_pidStopping.getPID(e);
  287. // std::cout << "Stopping : e=" << e << ", desiredPID=" << desiredVelocity << ", PID: " << m_pidStopping.ToString() << std::endl;
  288. if(desiredVelocity > max_velocity)
  289. desiredVelocity = max_velocity;
  290. else if(desiredVelocity < m_params.minSpeed)
  291. desiredVelocity = 0;
  292. for(unsigned int i = 0; i < m_Path.size(); i++)
  293. m_Path.at(i).v = desiredVelocity;
  294. return desiredVelocity;
  295. }
  296. else if(beh.state == FOLLOW_STATE)
  297. {
  298. double deceleration_critical = 0;
  299. double inv_time = 2.0*((beh.followDistance- (critical_long_front_distance+m_params.additionalBrakingDistance))-CurrStatus.speed);
  300. if(inv_time <= 0)
  301. deceleration_critical = m_CarInfo.max_deceleration;
  302. else
  303. deceleration_critical = CurrStatus.speed*CurrStatus.speed/inv_time;
  304. if(deceleration_critical > 0) deceleration_critical = -deceleration_critical;
  305. if(deceleration_critical < - m_CarInfo.max_acceleration) deceleration_critical = - m_CarInfo.max_acceleration;
  306. double desiredVelocity = (deceleration_critical * dt) + CurrStatus.speed;
  307. if(desiredVelocity > m_params.maxSpeed)
  308. desiredVelocity = m_params.maxSpeed;
  309. if((desiredVelocity < 0.1 && desiredVelocity > -0.1) || beh.followDistance <= 0) //use only effective velocities
  310. desiredVelocity = 0;
  311. //std::cout << "Acc: V: " << desiredVelocity << ", Accel: " << deceleration_critical<< std::endl;
  312. for(unsigned int i = 0; i < m_Path.size(); i++)
  313. m_Path.at(i).v = desiredVelocity;
  314. return desiredVelocity;
  315. }
  316. else if(beh.state == FORWARD_STATE || beh.state == OBSTACLE_AVOIDANCE_STATE )
  317. {
  318. double target_velocity = max_velocity;
  319. bool bSlowBecauseChange=false;
  320. if(m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeTrajectory != m_pCurrentBehaviorState->GetCalcParams()->iCentralTrajectory)
  321. {
  322. target_velocity*=0.5;
  323. bSlowBecauseChange = true;
  324. }
  325. double e = target_velocity - CurrStatus.speed;
  326. double desiredVelocity = m_pidVelocity.getPID(e);
  327. if(desiredVelocity>max_velocity)
  328. desiredVelocity = max_velocity;
  329. else if(desiredVelocity < m_params.minSpeed)
  330. desiredVelocity = 0;
  331. for(unsigned int i = 0; i < m_Path.size(); i++)
  332. m_Path.at(i).v = desiredVelocity;
  333. //std::cout << "Target Velocity: " << desiredVelocity << ", Change Slowdown: " << bSlowBecauseChange << std::endl;
  334. return desiredVelocity;
  335. }
  336. else if(beh.state == STOP_SIGN_WAIT_STATE || beh.state == TRAFFIC_LIGHT_WAIT_STATE)
  337. {
  338. double target_velocity = 0;
  339. for(unsigned int i = 0; i < m_Path.size(); i++)
  340. m_Path.at(i).v = target_velocity;
  341. return target_velocity;
  342. }
  343. else
  344. {
  345. double target_velocity = 0;
  346. for(unsigned int i = 0; i < m_Path.size(); i++)
  347. m_Path.at(i).v = target_velocity;
  348. return target_velocity;
  349. }
  350. return max_velocity;
  351. }
  352. PlannerHNS::BehaviorState DecisionMaker::DoOneStep(
  353. const double& dt,
  354. const PlannerHNS::WayPoint currPose,
  355. const PlannerHNS::VehicleState& vehicleState,
  356. const int& goalID,
  357. const std::vector<TrafficLight>& trafficLight,
  358. const TrajectoryCost& tc,
  359. const bool& bEmergencyStop)
  360. {
  361. PlannerHNS::BehaviorState beh;
  362. state = currPose;
  363. m_TotalPath.clear();
  364. for(unsigned int i = 0; i < m_TotalOriginalPath.size(); i++)
  365. {
  366. t_centerTrajectorySmoothed.clear();
  367. PlannerHNS::PlanningHelpers::ExtractPartFromPointToDistanceDirectionFast(m_TotalOriginalPath.at(i), state, m_params.horizonDistance , m_params.pathDensity , t_centerTrajectorySmoothed);
  368. m_TotalPath.push_back(t_centerTrajectorySmoothed);
  369. }
  370. if(m_TotalPath.size()==0) return beh;
  371. UpdateCurrentLane(m_MaxLaneSearchDistance);
  372. CalculateImportantParameterForDecisionMaking(vehicleState, goalID, bEmergencyStop, trafficLight, tc);
  373. beh = GenerateBehaviorState(vehicleState);
  374. beh.bNewPlan = SelectSafeTrajectory();
  375. beh.maxVelocity = UpdateVelocityDirectlyToTrajectory(beh, vehicleState, dt);
  376. //std::cout << "Eval_i: " << tc.index << ", Curr_i: " << m_pCurrentBehaviorState->GetCalcParams()->iCurrSafeTrajectory << ", Prev_i: " << m_pCurrentBehaviorState->GetCalcParams()->iPrevSafeTrajectory << std::endl;
  377. return beh;
  378. }
  379. } /* namespace PlannerHNS */