123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518 |
- /// \file BehaviorStateMachine.cpp
- /// \author Hatem Darweesh
- /// \brief OpenPlanner's state machine implementation for different driving behaviors
- /// \date Jun 19, 2016
- #include "op_planner/BehaviorStateMachine.h"
- #include "op_utility/UtilityH.h"
- #include <iostream>
- using namespace UtilityHNS;
- namespace PlannerHNS
- {
- BehaviorStateMachine::BehaviorStateMachine(PlanningParams* pParams, PreCalculatedConditions* pPreCalcVal, BehaviorStateMachine* nextState)
- {
- m_Behavior = INITIAL_STATE;
- m_currentStopSignID = -1;
- m_currentTrafficLightID = -1;
- decisionMakingTime = 0.0;
- decisionMakingCount = 1;
- m_zero_velocity = 0.1;
- if(!pPreCalcVal)
- m_pCalculatedValues = new PreCalculatedConditions();
- else
- m_pCalculatedValues = pPreCalcVal;
- if(!pParams)
- m_pParams = new PlanningParams;
- else
- m_pParams = pParams;
- if(nextState)
- pNextStates.push_back(nextState);
- pNextStates.push_back(this);
- Init();
- }
- void BehaviorStateMachine::InsertNextState(BehaviorStateMachine* nextState)
- {
- if(nextState)
- pNextStates.push_back(nextState);
- }
- void BehaviorStateMachine::UpdateLogCount(BehaviorStateMachine* pState)
- {
- if(!pState) return;
- bool bFound = false;
- for(unsigned int i = 0; i < m_BehaviorsLog.size(); i++)
- {
- if(m_BehaviorsLog.at(i).first->m_Behavior == pState->m_Behavior)
- {
- m_BehaviorsLog.at(i).second++;
- bFound = true;
- break;
- }
- }
- if(!bFound)
- {
- m_BehaviorsLog.push_back(std::make_pair(pState, 1));
- }
- }
- BehaviorStateMachine* BehaviorStateMachine::FindBestState(int nMinCount)
- {
- for(unsigned int i = 0; i < m_BehaviorsLog.size(); i++)
- {
- if(m_BehaviorsLog.at(i).second >= nMinCount)
- {
- //std::cout << "Found Next Beh: " << m_BehaviorsLog.at(i).first->m_Behavior << ", Count: " << m_BehaviorsLog.at(i).second << ", LogSize: " << m_BehaviorsLog.size() << std::endl;
- return m_BehaviorsLog.at(i).first;
- }
- }
- return nullptr;
- }
- BehaviorStateMachine* BehaviorStateMachine::FindBehaviorState(const STATE_TYPE& behavior)
- {
- for(unsigned int i = 0 ; i < pNextStates.size(); i++)
- {
- BehaviorStateMachine* pState = pNextStates.at(i);
- if(pState && behavior == pState->m_Behavior )
- {
- //UpdateLogCount(pState);
- //pState = FindBestState(decisionMakingCount);
- if(pState == 0) return this;
- m_BehaviorsLog.clear();
- pState->ResetTimer();
- return pState;
- }
- }
- return nullptr;
- }
- void BehaviorStateMachine::Init()
- {
- UtilityH::GetTickCount(m_StateTimer);
- }
- void BehaviorStateMachine::ResetTimer()
- {
- UtilityH::GetTickCount(m_StateTimer);
- }
- BehaviorStateMachine::~BehaviorStateMachine()
- {
- }
- BehaviorStateMachine* ForwardState::GetNextState()
- {
- if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime)
- return this; //return this behavior only , without reset
- PreCalculatedConditions* pCParams = GetCalcParams();
- if(pCParams->currentGoalID != pCParams->prevGoalID)
- return FindBehaviorState(GOAL_STATE);
- else if(m_pParams->enableSwerving
- && pCParams->distanceToNext <= m_pParams->minDistanceToAvoid
- && !pCParams->bFullyBlock
- && (pCParams->iCurrSafeTrajectory != pCParams->iPrevSafeTrajectory || pCParams->iCurrSafeLane != pCParams->iPrevSafeLane)
- )
- return FindBehaviorState(OBSTACLE_AVOIDANCE_STATE);
- else if(m_pParams->enableTrafficLightBehavior
- && pCParams->currentTrafficLightID > 0
- && pCParams->bTrafficIsRed
- && pCParams->currentTrafficLightID != pCParams->prevTrafficLightID)
- return FindBehaviorState(TRAFFIC_LIGHT_STOP_STATE);
- else if(m_pParams->enableStopSignBehavior
- && pCParams->currentStopSignID > 0
- && pCParams->currentStopSignID != pCParams->prevStopSignID)
- return FindBehaviorState(STOP_SIGN_STOP_STATE);
- else if(m_pParams->enableFollowing
- && pCParams->bFullyBlock)
- return FindBehaviorState(FOLLOW_STATE);
- // else if(pCParams->distanceToNext <= m_pParams->maxDistanceToAvoid)
- // return FindBehaviorState(STOPPING_STATE);
- else
- {
- if(pCParams->iCurrSafeTrajectory == pCParams->iCentralTrajectory
- && pCParams->iPrevSafeTrajectory != pCParams->iCurrSafeTrajectory)
- pCParams->bRePlan = true;
- return FindBehaviorState(this->m_Behavior); // return and reset
- }
- }
- BehaviorStateMachine* MissionAccomplishedState::GetNextState()
- {
- return FindBehaviorState(this->m_Behavior); // return and reset
- }
- BehaviorStateMachine* StopState::GetNextState()
- {
- if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime)
- return this;
- PreCalculatedConditions* pCParams = GetCalcParams();
- if(pCParams->distanceToNext > m_pParams->maxDistanceToAvoid)
- return FindBehaviorState(FORWARD_STATE);
- else
- return FindBehaviorState(this->m_Behavior); // return and reset
- }
- BehaviorStateMachine* TrafficLightStopState::GetNextState()
- {
- if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime)
- return this;
- PreCalculatedConditions* pCParams = GetCalcParams();
- if(!pCParams->bTrafficIsRed)
- {
- pCParams->prevTrafficLightID = pCParams->currentTrafficLightID;
- return FindBehaviorState(FORWARD_STATE);
- }
- else if(pCParams->bTrafficIsRed && pCParams->currentVelocity <= m_zero_velocity)
- return FindBehaviorState(TRAFFIC_LIGHT_WAIT_STATE);
- else
- return FindBehaviorState(this->m_Behavior); // return and reset
- }
- BehaviorStateMachine* TrafficLightWaitState::GetNextState()
- {
- if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime)
- return this;
- PreCalculatedConditions* pCParams = GetCalcParams();
- if(!pCParams->bTrafficIsRed)
- {
- pCParams->prevTrafficLightID = pCParams->currentTrafficLightID;
- return FindBehaviorState(FORWARD_STATE);
- }
- else if(pCParams->currentVelocity > m_zero_velocity)
- return FindBehaviorState(TRAFFIC_LIGHT_STOP_STATE);
- else
- return FindBehaviorState(this->m_Behavior); // return and reset
- }
- BehaviorStateMachine* StopSignStopState::GetNextState()
- {
- if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime)
- return this;
- PreCalculatedConditions* pCParams = GetCalcParams();
- //std::cout << "From Stop Beh D: " << pCParams->distanceToStop() << ", Prev LineID: " << pCParams->prevStopSignID << ", Curr SignID: " << pCParams->currentStopSignID << std::endl;
- if(pCParams->currentVelocity < m_zero_velocity)
- return FindBehaviorState(STOP_SIGN_WAIT_STATE);
- else
- return FindBehaviorState(this->m_Behavior); // return and reset
- }
- BehaviorStateMachine* StopSignWaitState::GetNextState()
- {
- if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime)
- return this;
- PreCalculatedConditions* pCParams = GetCalcParams();
- //std::cout << "From Wait Beh D: " << pCParams->distanceToStop() << ", Prev LineID: " << pCParams->prevStopSignID << ", Curr SignID: " << pCParams->currentStopSignID << std::endl;
- pCParams->prevStopSignID = pCParams->currentStopSignID;
- return FindBehaviorState(FORWARD_STATE);
- }
- BehaviorStateMachine* WaitState::GetNextState()
- {
- if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime)
- return this;
- //PreCalculatedConditions* pCParams = GetCalcParams();
- return FindBehaviorState(FORWARD_STATE);
- }
- BehaviorStateMachine* InitState::GetNextState()
- {
- if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime)
- return this;
- PreCalculatedConditions* pCParams = GetCalcParams();
- if(pCParams->bOutsideControl == 1)
- {
- pCParams->prevGoalID = pCParams->currentGoalID;
- return FindBehaviorState(FORWARD_STATE);
- }
- else
- return FindBehaviorState(this->m_Behavior); // return and reset
- }
- BehaviorStateMachine* FollowState::GetNextState()
- {
- if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime)
- return this;
- PreCalculatedConditions* pCParams = GetCalcParams();
- //std::cout << "Following State >> followDistance: " << pCParams->distanceToNext << ", followSpeed: " << pCParams->velocityOfNext << std::endl;
- if(m_pParams->enableTrafficLightBehavior
- && pCParams->currentTrafficLightID > 0
- && pCParams->bTrafficIsRed
- && pCParams->currentTrafficLightID != pCParams->prevTrafficLightID)
- return FindBehaviorState(TRAFFIC_LIGHT_STOP_STATE);
- else if(m_pParams->enableStopSignBehavior
- && pCParams->currentStopSignID > 0
- && pCParams->currentStopSignID != pCParams->prevStopSignID)
- return FindBehaviorState(STOP_SIGN_STOP_STATE);
- else if(pCParams->currentGoalID != pCParams->prevGoalID
- || !pCParams->bFullyBlock)
- return FindBehaviorState(FORWARD_STATE);
- else
- return FindBehaviorState(this->m_Behavior); // return and reset
- }
- BehaviorStateMachine* SwerveState::GetNextState()
- {
- if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime)
- return this;
- PreCalculatedConditions* pCParams = GetCalcParams();
- if(pCParams->distanceToNext > 0
- && pCParams->distanceToNext < m_pParams->minDistanceToAvoid
- && !pCParams->bFullyBlock
- && pCParams->iCurrSafeTrajectory != pCParams->iPrevSafeTrajectory)
- return FindBehaviorState(this->m_Behavior);
- else
- return FindBehaviorState(FORWARD_STATE);
- }
- BehaviorStateMachine* GoalState::GetNextState()
- {
- if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime)
- return this;
- PreCalculatedConditions* pCParams = GetCalcParams();
- if(pCParams->currentGoalID == -1)
- return FindBehaviorState(FINISH_STATE);
- else if(pCParams->currentGoalID != pCParams->prevGoalID)
- {
- pCParams->prevGoalID = pCParams->currentGoalID;
- return FindBehaviorState(FORWARD_STATE);
- }
- else
- return FindBehaviorState(this->m_Behavior); // return and reset
- }
- BehaviorStateMachine* ForwardStateII::GetNextState()
- {
- PreCalculatedConditions* pCParams = GetCalcParams();
- if(pCParams->currentGoalID != pCParams->prevGoalID)
- return FindBehaviorState(GOAL_STATE);
- else if(m_pParams->enableTrafficLightBehavior
- && pCParams->currentTrafficLightID > 0
- && pCParams->bTrafficIsRed
- && pCParams->currentTrafficLightID != pCParams->prevTrafficLightID)
- return FindBehaviorState(TRAFFIC_LIGHT_STOP_STATE);
- else if(m_pParams->enableStopSignBehavior
- && pCParams->currentStopSignID > 0
- && pCParams->currentStopSignID != pCParams->prevStopSignID)
- return FindBehaviorState(STOP_SIGN_STOP_STATE);
- else if(m_pParams->enableFollowing && pCParams->bFullyBlock)
- return FindBehaviorState(FOLLOW_STATE);
- else if(m_pParams->enableSwerving
- && pCParams->distanceToNext <= m_pParams->minDistanceToAvoid
- && !pCParams->bFullyBlock
- && pCParams->iCurrSafeTrajectory != pCParams->iPrevSafeTrajectory)
- return FindBehaviorState(OBSTACLE_AVOIDANCE_STATE);
- else
- return FindBehaviorState(this->m_Behavior);
- }
- BehaviorStateMachine* FollowStateII::GetNextState()
- {
- PreCalculatedConditions* pCParams = GetCalcParams();
- if(pCParams->currentGoalID != pCParams->prevGoalID)
- return FindBehaviorState(GOAL_STATE);
- else if(m_pParams->enableTrafficLightBehavior
- && pCParams->currentTrafficLightID > 0
- && pCParams->bTrafficIsRed
- && pCParams->currentTrafficLightID != pCParams->prevTrafficLightID)
- return FindBehaviorState(TRAFFIC_LIGHT_STOP_STATE);
- else if(m_pParams->enableStopSignBehavior
- && pCParams->currentStopSignID > 0
- && pCParams->currentStopSignID != pCParams->prevStopSignID)
- return FindBehaviorState(STOP_SIGN_STOP_STATE);
- else if(m_pParams->enableSwerving
- && pCParams->distanceToNext <= m_pParams->minDistanceToAvoid
- && !pCParams->bFullyBlock
- && pCParams->iCurrSafeTrajectory != pCParams->iPrevSafeTrajectory)
- return FindBehaviorState(OBSTACLE_AVOIDANCE_STATE);
- else if(!pCParams->bFullyBlock)
- return FindBehaviorState(FORWARD_STATE);
- else
- return FindBehaviorState(this->m_Behavior); // return and reset
- }
- BehaviorStateMachine* SwerveStateII::GetNextState()
- {
- PreCalculatedConditions* pCParams = GetCalcParams();
- pCParams->iPrevSafeTrajectory = pCParams->iCurrSafeTrajectory;
- pCParams->bRePlan = true;
- return FindBehaviorState(FORWARD_STATE);
- }
- BehaviorStateMachine* InitStateII::GetNextState()
- {
- PreCalculatedConditions* pCParams = GetCalcParams();
- if(pCParams->currentGoalID > 0)
- return FindBehaviorState(FORWARD_STATE);
- else
- return FindBehaviorState(this->m_Behavior);
- }
- BehaviorStateMachine* GoalStateII::GetNextState()
- {
- PreCalculatedConditions* pCParams = GetCalcParams();
- if(pCParams->currentGoalID == -1)
- return FindBehaviorState(FINISH_STATE);
- else
- {
- pCParams->prevGoalID = pCParams->currentGoalID;
- return FindBehaviorState(FORWARD_STATE);
- }
- }
- BehaviorStateMachine* MissionAccomplishedStateII::GetNextState()
- {
- return FindBehaviorState(this->m_Behavior);
- }
- BehaviorStateMachine* StopSignStopStateII::GetNextState()
- {
- PreCalculatedConditions* pCParams = GetCalcParams();
- if(pCParams->currentGoalID != pCParams->prevGoalID)
- return FindBehaviorState(GOAL_STATE);
- else if(pCParams->currentVelocity < m_zero_velocity)
- return FindBehaviorState(STOP_SIGN_WAIT_STATE);
- else
- return FindBehaviorState(this->m_Behavior); // return and reset
- }
- BehaviorStateMachine* StopSignWaitStateII::GetNextState()
- {
- if(UtilityH::GetTimeDiffNow(m_StateTimer) < decisionMakingTime)
- return this;
- PreCalculatedConditions* pCParams = GetCalcParams();
- pCParams->prevStopSignID = pCParams->currentStopSignID;
- return FindBehaviorState(FORWARD_STATE);
- }
- BehaviorStateMachine* TrafficLightStopStateII::GetNextState()
- {
- PreCalculatedConditions* pCParams = GetCalcParams();
- //std::cout << "Stopping for trafficLight " << std::endl;
- if(!pCParams->bTrafficIsRed)
- {
- //std::cout << "Color Changed Stopping for trafficLight " << std::endl;
- pCParams->prevTrafficLightID = pCParams->currentTrafficLightID;
- return FindBehaviorState(FORWARD_STATE);
- }
- else if(pCParams->bTrafficIsRed && pCParams->currentVelocity <= m_zero_velocity)
- {
- //std::cout << "Velocity Changed Stopping for trafficLight (" <<pCParams->currentVelocity << ", " << m_zero_velocity << ")" << std::endl;
- return FindBehaviorState(TRAFFIC_LIGHT_WAIT_STATE);
- }
- else
- {
- return FindBehaviorState(this->m_Behavior); // return and reset
- }
- }
- BehaviorStateMachine* TrafficLightWaitStateII::GetNextState()
- {
- PreCalculatedConditions* pCParams = GetCalcParams();
- //std::cout << "Wait for trafficLight " << std::endl;
- if(!pCParams->bTrafficIsRed)
- {
- pCParams->prevTrafficLightID = pCParams->currentTrafficLightID;
- return FindBehaviorState(FORWARD_STATE);
- }
- // else if(pCParams->currentVelocity > m_zero_velocity)
- // return FindBehaviorState(TRAFFIC_LIGHT_STOP_STATE);
- else
- return FindBehaviorState(this->m_Behavior); // return and reset
- }
- } /* namespace PlannerHNS */
|