BehaviorStateMachine.cpp 14 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518
  1. /// \file BehaviorStateMachine.cpp
  2. /// \author Hatem Darweesh
  3. /// \brief OpenPlanner's state machine implementation for different driving behaviors
  4. /// \date Jun 19, 2016
  5. #include "op_planner/BehaviorStateMachine.h"
  6. #include "op_utility/UtilityH.h"
  7. #include <iostream>
  8. using namespace UtilityHNS;
  9. namespace PlannerHNS
  10. {
  11. BehaviorStateMachine::BehaviorStateMachine(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* nextState)
  12. {
  13. m_Behavior = INITIAL_STATE;
  14. m_currentStopSignID = -1;
  15. m_currentTrafficLightID = -1;
  16. decisionMakingTime = 0.0;
  17. decisionMakingCount = 1;
  18. m_zero_velocity = 0.1;
  19. if(!pPreCalcVal)
  20. m_pCalculatedValues = new PreCalculatedConditions();
  21. else
  22. m_pCalculatedValues = pPreCalcVal;
  23. if(!pParams)
  24. m_pParams = new PlanningParams;
  25. else
  26. m_pParams = pParams;
  27. if(nextState)
  28. pNextStates.push_back(nextState);
  29. pNextStates.push_back(this);
  30. Init();
  31. }
  32. void BehaviorStateMachine::InsertNextState(BehaviorStateMachine* nextState)
  33. {
  34. if(nextState)
  35. pNextStates.push_back(nextState);
  36. }
  37. void BehaviorStateMachine::UpdateLogCount(BehaviorStateMachine* pState)
  38. {
  39. if(!pState) return;
  40. bool bFound = false;
  41. for(unsigned int i = 0; i < m_BehaviorsLog.size(); i++)
  42. {
  43. if(m_BehaviorsLog.at(i).first->m_Behavior == pState->m_Behavior)
  44. {
  45. m_BehaviorsLog.at(i).second++;
  46. bFound = true;
  47. break;
  48. }
  49. }
  50. if(!bFound)
  51. {
  52. m_BehaviorsLog.push_back(std::make_pair(pState, 1));
  53. }
  54. }
  55. BehaviorStateMachine* BehaviorStateMachine::FindBestState(int nMinCount)
  56. {
  57. for(unsigned int i = 0; i < m_BehaviorsLog.size(); i++)
  58. {
  59. if(m_BehaviorsLog.at(i).second >= nMinCount)
  60. {
  61. //std::cout << "Found Next Beh: " << m_BehaviorsLog.at(i).first->m_Behavior << ", Count: " << m_BehaviorsLog.at(i).second << ", LogSize: " << m_BehaviorsLog.size() << std::endl;
  62. return m_BehaviorsLog.at(i).first;
  63. }
  64. }
  65. return nullptr;
  66. }
  67. BehaviorStateMachine* BehaviorStateMachine::FindBehaviorState(const STATE_TYPE& behavior)
  68. {
  69. for(unsigned int i = 0 ; i < pNextStates.size(); i++)
  70. {
  71. BehaviorStateMachine* pState = pNextStates.at(i);
  72. if(pState && behavior == pState->m_Behavior )
  73. {
  74. //UpdateLogCount(pState);
  75. //pState = FindBestState(decisionMakingCount);
  76. if(pState == 0) return this;
  77. m_BehaviorsLog.clear();
  78. pState->ResetTimer();
  79. return pState;
  80. }
  81. }
  82. return nullptr;
  83. }
  84. void BehaviorStateMachine::Init()
  85. {
  86. UtilityH::GetTickCount(m_StateTimer);
  87. }
  88. void BehaviorStateMachine::ResetTimer()
  89. {
  90. UtilityH::GetTickCount(m_StateTimer);
  91. }
  92. BehaviorStateMachine::~BehaviorStateMachine()
  93. {
  94. }
  95. BehaviorStateMachine* ForwardState::GetNextState()
  96. {
  97. if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime)
  98. return this; //return this behavior only , without reset
  99. PreCalculatedConditions* pCParams = GetCalcParams();
  100. if(pCParams->currentGoalID != pCParams->prevGoalID)
  101. return FindBehaviorState(GOAL_STATE);
  102. else if(m_pParams->enableSwerving
  103. && pCParams->distanceToNext <= m_pParams->minDistanceToAvoid
  104. && !pCParams->bFullyBlock
  105. && (pCParams->iCurrSafeTrajectory != pCParams->iPrevSafeTrajectory || pCParams->iCurrSafeLane != pCParams->iPrevSafeLane)
  106. )
  107. return FindBehaviorState(OBSTACLE_AVOIDANCE_STATE);
  108. else if(m_pParams->enableTrafficLightBehavior
  109. && pCParams->currentTrafficLightID > 0
  110. && pCParams->bTrafficIsRed
  111. && pCParams->currentTrafficLightID != pCParams->prevTrafficLightID)
  112. return FindBehaviorState(TRAFFIC_LIGHT_STOP_STATE);
  113. else if(m_pParams->enableStopSignBehavior
  114. && pCParams->currentStopSignID > 0
  115. && pCParams->currentStopSignID != pCParams->prevStopSignID)
  116. return FindBehaviorState(STOP_SIGN_STOP_STATE);
  117. else if(m_pParams->enableFollowing
  118. && pCParams->bFullyBlock)
  119. return FindBehaviorState(FOLLOW_STATE);
  120. // else if(pCParams->distanceToNext <= m_pParams->maxDistanceToAvoid)
  121. // return FindBehaviorState(STOPPING_STATE);
  122. else
  123. {
  124. if(pCParams->iCurrSafeTrajectory == pCParams->iCentralTrajectory
  125. && pCParams->iPrevSafeTrajectory != pCParams->iCurrSafeTrajectory)
  126. pCParams->bRePlan = true;
  127. return FindBehaviorState(this->m_Behavior); // return and reset
  128. }
  129. }
  130. BehaviorStateMachine* MissionAccomplishedState::GetNextState()
  131. {
  132. return FindBehaviorState(this->m_Behavior); // return and reset
  133. }
  134. BehaviorStateMachine* StopState::GetNextState()
  135. {
  136. if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime)
  137. return this;
  138. PreCalculatedConditions* pCParams = GetCalcParams();
  139. if(pCParams->distanceToNext > m_pParams->maxDistanceToAvoid)
  140. return FindBehaviorState(FORWARD_STATE);
  141. else
  142. return FindBehaviorState(this->m_Behavior); // return and reset
  143. }
  144. BehaviorStateMachine* TrafficLightStopState::GetNextState()
  145. {
  146. if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime)
  147. return this;
  148. PreCalculatedConditions* pCParams = GetCalcParams();
  149. if(!pCParams->bTrafficIsRed)
  150. {
  151. pCParams->prevTrafficLightID = pCParams->currentTrafficLightID;
  152. return FindBehaviorState(FORWARD_STATE);
  153. }
  154. else if(pCParams->bTrafficIsRed && pCParams->currentVelocity <= m_zero_velocity)
  155. return FindBehaviorState(TRAFFIC_LIGHT_WAIT_STATE);
  156. else
  157. return FindBehaviorState(this->m_Behavior); // return and reset
  158. }
  159. BehaviorStateMachine* TrafficLightWaitState::GetNextState()
  160. {
  161. if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime)
  162. return this;
  163. PreCalculatedConditions* pCParams = GetCalcParams();
  164. if(!pCParams->bTrafficIsRed)
  165. {
  166. pCParams->prevTrafficLightID = pCParams->currentTrafficLightID;
  167. return FindBehaviorState(FORWARD_STATE);
  168. }
  169. else if(pCParams->currentVelocity > m_zero_velocity)
  170. return FindBehaviorState(TRAFFIC_LIGHT_STOP_STATE);
  171. else
  172. return FindBehaviorState(this->m_Behavior); // return and reset
  173. }
  174. BehaviorStateMachine* StopSignStopState::GetNextState()
  175. {
  176. if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime)
  177. return this;
  178. PreCalculatedConditions* pCParams = GetCalcParams();
  179. //std::cout << "From Stop Beh D: " << pCParams->distanceToStop() << ", Prev LineID: " << pCParams->prevStopSignID << ", Curr SignID: " << pCParams->currentStopSignID << std::endl;
  180. if(pCParams->currentVelocity < m_zero_velocity)
  181. return FindBehaviorState(STOP_SIGN_WAIT_STATE);
  182. else
  183. return FindBehaviorState(this->m_Behavior); // return and reset
  184. }
  185. BehaviorStateMachine* StopSignWaitState::GetNextState()
  186. {
  187. if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime)
  188. return this;
  189. PreCalculatedConditions* pCParams = GetCalcParams();
  190. //std::cout << "From Wait Beh D: " << pCParams->distanceToStop() << ", Prev LineID: " << pCParams->prevStopSignID << ", Curr SignID: " << pCParams->currentStopSignID << std::endl;
  191. pCParams->prevStopSignID = pCParams->currentStopSignID;
  192. return FindBehaviorState(FORWARD_STATE);
  193. }
  194. BehaviorStateMachine* WaitState::GetNextState()
  195. {
  196. if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime)
  197. return this;
  198. //PreCalculatedConditions* pCParams = GetCalcParams();
  199. return FindBehaviorState(FORWARD_STATE);
  200. }
  201. BehaviorStateMachine* InitState::GetNextState()
  202. {
  203. if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime)
  204. return this;
  205. PreCalculatedConditions* pCParams = GetCalcParams();
  206. if(pCParams->bOutsideControl == 1)
  207. {
  208. pCParams->prevGoalID = pCParams->currentGoalID;
  209. return FindBehaviorState(FORWARD_STATE);
  210. }
  211. else
  212. return FindBehaviorState(this->m_Behavior); // return and reset
  213. }
  214. BehaviorStateMachine* FollowState::GetNextState()
  215. {
  216. if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime)
  217. return this;
  218. PreCalculatedConditions* pCParams = GetCalcParams();
  219. //std::cout << "Following State >> followDistance: " << pCParams->distanceToNext << ", followSpeed: " << pCParams->velocityOfNext << std::endl;
  220. if(m_pParams->enableTrafficLightBehavior
  221. && pCParams->currentTrafficLightID > 0
  222. && pCParams->bTrafficIsRed
  223. && pCParams->currentTrafficLightID != pCParams->prevTrafficLightID)
  224. return FindBehaviorState(TRAFFIC_LIGHT_STOP_STATE);
  225. else if(m_pParams->enableStopSignBehavior
  226. && pCParams->currentStopSignID > 0
  227. && pCParams->currentStopSignID != pCParams->prevStopSignID)
  228. return FindBehaviorState(STOP_SIGN_STOP_STATE);
  229. else if(pCParams->currentGoalID != pCParams->prevGoalID
  230. || !pCParams->bFullyBlock)
  231. return FindBehaviorState(FORWARD_STATE);
  232. else
  233. return FindBehaviorState(this->m_Behavior); // return and reset
  234. }
  235. BehaviorStateMachine* SwerveState::GetNextState()
  236. {
  237. if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime)
  238. return this;
  239. PreCalculatedConditions* pCParams = GetCalcParams();
  240. if(pCParams->distanceToNext > 0
  241. && pCParams->distanceToNext < m_pParams->minDistanceToAvoid
  242. && !pCParams->bFullyBlock
  243. && pCParams->iCurrSafeTrajectory != pCParams->iPrevSafeTrajectory)
  244. return FindBehaviorState(this->m_Behavior);
  245. else
  246. return FindBehaviorState(FORWARD_STATE);
  247. }
  248. BehaviorStateMachine* GoalState::GetNextState()
  249. {
  250. if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime)
  251. return this;
  252. PreCalculatedConditions* pCParams = GetCalcParams();
  253. if(pCParams->currentGoalID == -1)
  254. return FindBehaviorState(FINISH_STATE);
  255. else if(pCParams->currentGoalID != pCParams->prevGoalID)
  256. {
  257. pCParams->prevGoalID = pCParams->currentGoalID;
  258. return FindBehaviorState(FORWARD_STATE);
  259. }
  260. else
  261. return FindBehaviorState(this->m_Behavior); // return and reset
  262. }
  263. BehaviorStateMachine* ForwardStateII::GetNextState()
  264. {
  265. PreCalculatedConditions* pCParams = GetCalcParams();
  266. if(pCParams->currentGoalID != pCParams->prevGoalID)
  267. return FindBehaviorState(GOAL_STATE);
  268. else if(m_pParams->enableTrafficLightBehavior
  269. && pCParams->currentTrafficLightID > 0
  270. && pCParams->bTrafficIsRed
  271. && pCParams->currentTrafficLightID != pCParams->prevTrafficLightID)
  272. return FindBehaviorState(TRAFFIC_LIGHT_STOP_STATE);
  273. else if(m_pParams->enableStopSignBehavior
  274. && pCParams->currentStopSignID > 0
  275. && pCParams->currentStopSignID != pCParams->prevStopSignID)
  276. return FindBehaviorState(STOP_SIGN_STOP_STATE);
  277. else if(m_pParams->enableFollowing && pCParams->bFullyBlock)
  278. return FindBehaviorState(FOLLOW_STATE);
  279. else if(m_pParams->enableSwerving
  280. && pCParams->distanceToNext <= m_pParams->minDistanceToAvoid
  281. && !pCParams->bFullyBlock
  282. && pCParams->iCurrSafeTrajectory != pCParams->iPrevSafeTrajectory)
  283. return FindBehaviorState(OBSTACLE_AVOIDANCE_STATE);
  284. else
  285. return FindBehaviorState(this->m_Behavior);
  286. }
  287. BehaviorStateMachine* FollowStateII::GetNextState()
  288. {
  289. PreCalculatedConditions* pCParams = GetCalcParams();
  290. if(pCParams->currentGoalID != pCParams->prevGoalID)
  291. return FindBehaviorState(GOAL_STATE);
  292. else if(m_pParams->enableTrafficLightBehavior
  293. && pCParams->currentTrafficLightID > 0
  294. && pCParams->bTrafficIsRed
  295. && pCParams->currentTrafficLightID != pCParams->prevTrafficLightID)
  296. return FindBehaviorState(TRAFFIC_LIGHT_STOP_STATE);
  297. else if(m_pParams->enableStopSignBehavior
  298. && pCParams->currentStopSignID > 0
  299. && pCParams->currentStopSignID != pCParams->prevStopSignID)
  300. return FindBehaviorState(STOP_SIGN_STOP_STATE);
  301. else if(m_pParams->enableSwerving
  302. && pCParams->distanceToNext <= m_pParams->minDistanceToAvoid
  303. && !pCParams->bFullyBlock
  304. && pCParams->iCurrSafeTrajectory != pCParams->iPrevSafeTrajectory)
  305. return FindBehaviorState(OBSTACLE_AVOIDANCE_STATE);
  306. else if(!pCParams->bFullyBlock)
  307. return FindBehaviorState(FORWARD_STATE);
  308. else
  309. return FindBehaviorState(this->m_Behavior); // return and reset
  310. }
  311. BehaviorStateMachine* SwerveStateII::GetNextState()
  312. {
  313. PreCalculatedConditions* pCParams = GetCalcParams();
  314. pCParams->iPrevSafeTrajectory = pCParams->iCurrSafeTrajectory;
  315. pCParams->bRePlan = true;
  316. return FindBehaviorState(FORWARD_STATE);
  317. }
  318. BehaviorStateMachine* InitStateII::GetNextState()
  319. {
  320. PreCalculatedConditions* pCParams = GetCalcParams();
  321. if(pCParams->currentGoalID > 0)
  322. return FindBehaviorState(FORWARD_STATE);
  323. else
  324. return FindBehaviorState(this->m_Behavior);
  325. }
  326. BehaviorStateMachine* GoalStateII::GetNextState()
  327. {
  328. PreCalculatedConditions* pCParams = GetCalcParams();
  329. if(pCParams->currentGoalID == -1)
  330. return FindBehaviorState(FINISH_STATE);
  331. else
  332. {
  333. pCParams->prevGoalID = pCParams->currentGoalID;
  334. return FindBehaviorState(FORWARD_STATE);
  335. }
  336. }
  337. BehaviorStateMachine* MissionAccomplishedStateII::GetNextState()
  338. {
  339. return FindBehaviorState(this->m_Behavior);
  340. }
  341. BehaviorStateMachine* StopSignStopStateII::GetNextState()
  342. {
  343. PreCalculatedConditions* pCParams = GetCalcParams();
  344. if(pCParams->currentGoalID != pCParams->prevGoalID)
  345. return FindBehaviorState(GOAL_STATE);
  346. else if(pCParams->currentVelocity < m_zero_velocity)
  347. return FindBehaviorState(STOP_SIGN_WAIT_STATE);
  348. else
  349. return FindBehaviorState(this->m_Behavior); // return and reset
  350. }
  351. BehaviorStateMachine* StopSignWaitStateII::GetNextState()
  352. {
  353. if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime)
  354. return this;
  355. PreCalculatedConditions* pCParams = GetCalcParams();
  356. pCParams->prevStopSignID = pCParams->currentStopSignID;
  357. return FindBehaviorState(FORWARD_STATE);
  358. }
  359. BehaviorStateMachine* TrafficLightStopStateII::GetNextState()
  360. {
  361. PreCalculatedConditions* pCParams = GetCalcParams();
  362. //std::cout << "Stopping for trafficLight " << std::endl;
  363. if(!pCParams->bTrafficIsRed)
  364. {
  365. //std::cout << "Color Changed Stopping for trafficLight " << std::endl;
  366. pCParams->prevTrafficLightID = pCParams->currentTrafficLightID;
  367. return FindBehaviorState(FORWARD_STATE);
  368. }
  369. else if(pCParams->bTrafficIsRed && pCParams->currentVelocity <= m_zero_velocity)
  370. {
  371. //std::cout << "Velocity Changed Stopping for trafficLight (" <<pCParams->currentVelocity << ", " << m_zero_velocity << ")" << std::endl;
  372. return FindBehaviorState(TRAFFIC_LIGHT_WAIT_STATE);
  373. }
  374. else
  375. {
  376. return FindBehaviorState(this->m_Behavior); // return and reset
  377. }
  378. }
  379. BehaviorStateMachine* TrafficLightWaitStateII::GetNextState()
  380. {
  381. PreCalculatedConditions* pCParams = GetCalcParams();
  382. //std::cout << "Wait for trafficLight " << std::endl;
  383. if(!pCParams->bTrafficIsRed)
  384. {
  385. pCParams->prevTrafficLightID = pCParams->currentTrafficLightID;
  386. return FindBehaviorState(FORWARD_STATE);
  387. }
  388. // else if(pCParams->currentVelocity > m_zero_velocity)
  389. // return FindBehaviorState(TRAFFIC_LIGHT_STOP_STATE);
  390. else
  391. return FindBehaviorState(this->m_Behavior); // return and reset
  392. }
  393. } /* namespace PlannerHNS */