Autonomy Software C++ 24.5.1
Welcome to the Autonomy Software repository of the Mars Rover Design Team (MRDT) at Missouri University of Science and Technology (Missouri S&T)! API reference contains the source code and other resources for the development of the autonomy software for our Mars rover. The Autonomy Software project aims to compete in the University Rover Challenge (URC) by demonstrating advanced autonomous capabilities and robust navigation algorithms.
Loading...
Searching...
No Matches
statemachine::IdleState Class Reference

The IdleState class implements the Idle state for the Autonomy State Machine. More...

#include <IdleState.h>

Inheritance diagram for statemachine::IdleState:
Collaboration diagram for statemachine::IdleState:

Public Member Functions

 IdleState ()
 Construct a new State object.
 
void Run () override
 Run the state machine. Returns the next state.
 
States TriggerEvent (Event eEvent) override
 Trigger an event in the state machine. Returns the next state.
 
- Public Member Functions inherited from statemachine::State
 State (States eState)
 Construct a new State object.
 
virtual ~State ()=default
 Destroy the State object.
 
States GetState () const
 Accessor for the State private member.
 
virtual std::string ToString () const
 Accessor for the State private member. Returns the state as a string.
 
virtual bool operator== (const State &other) const
 Checks to see if the current state is equal to the passed state.
 
virtual bool operator!= (const State &other) const
 Checks to see if the current state is not equal to the passed state.
 

Protected Member Functions

void Start () override
 This method is called when the state is first started. It is used to initialize the state.
 
void Exit () override
 This method is called when the state is exited. It is used to clean up the state.
 

Private Attributes

geoops::RoverPose m_stStartRoverPose
 
bool m_bInitialized
 
std::vector< std::shared_ptr< TagDetector > > m_vTagDetectors
 

Detailed Description

The IdleState class implements the Idle state for the Autonomy State Machine.

Author
Eli Byrd (edbgk.nosp@m.k@ms.nosp@m.t.edu)
Date
2024-01-17

Constructor & Destructor Documentation

◆ IdleState()

statemachine::IdleState::IdleState ( )

Construct a new State object.

Author
Eli Byrd (edbgk.nosp@m.k@ms.nosp@m.t.edu)
Date
2024-01-17
61 : State(States::eIdle)
62 {
63 LOG_INFO(logging::g_qConsoleLogger, "Entering State: {}", ToString());
64
65 m_bInitialized = false;
66
67 if (!m_bInitialized)
68 {
69 Start();
70 m_bInitialized = true;
71 }
72 }
void Start() override
This method is called when the state is first started. It is used to initialize the state.
Definition IdleState.cpp:31
virtual std::string ToString() const
Accessor for the State private member. Returns the state as a string.
Definition State.hpp:207
State(States eState)
Construct a new State object.
Definition State.hpp:150
Here is the call graph for this function:

Member Function Documentation

◆ Start()

void statemachine::IdleState::Start ( )
overrideprotectedvirtual

This method is called when the state is first started. It is used to initialize the state.

Author
Eli Byrd (edbgk.nosp@m.k@ms.nosp@m.t.edu)
Date
2024-01-17

Reimplemented from statemachine::State.

32 {
33 // Schedule the next run of the state's logic
34 LOG_INFO(logging::g_qSharedLogger, "IdleState: Scheduling next run of state logic.");
35
36 // Get tag detectors.
37 m_vTagDetectors = {globals::g_pTagDetectionHandler->GetTagDetector(TagDetectionHandler::TagDetectors::eHeadMainCam)};
38 }
std::shared_ptr< TagDetector > GetTagDetector(TagDetectors eDetectorName)
Accessor for TagDetector detectors.
Definition TagDetectionHandler.cpp:132
Here is the call graph for this function:
Here is the caller graph for this function:

◆ Exit()

void statemachine::IdleState::Exit ( )
overrideprotectedvirtual

This method is called when the state is exited. It is used to clean up the state.

Author
Eli Byrd (edbgk.nosp@m.k@ms.nosp@m.t.edu)
Date
2024-01-17

Reimplemented from statemachine::State.

49 {
50 // Clean up the state before exiting
51 LOG_INFO(logging::g_qSharedLogger, "IdleState: Exiting state.");
52 }
Here is the caller graph for this function:

◆ Run()

void statemachine::IdleState::Run ( )
overridevirtual

Run the state machine. Returns the next state.

Author
Eli Byrd (edbgk.nosp@m.k@ms.nosp@m.t.edu)
Date
2024-01-17

Implements statemachine::State.

81 {
82 // Submit logger message.
83 LOG_DEBUG(logging::g_qSharedLogger, "IdleState: Running state-specific behavior.");
84
85 // Create instance variables.
86 geoops::RoverPose stCurrentRoverPose = globals::g_pWaypointHandler->SmartRetrieveRoverPose();
87
88 // Calculate distance from current position to position when idle state was entered.
89 geoops::GeoMeasurement stMeasurement = geoops::CalculateGeoMeasurement(m_stStartRoverPose.GetGPSCoordinate(), stCurrentRoverPose.GetGPSCoordinate());
90 // Check if the rover is still moving.
91 if (stMeasurement.dDistanceMeters > 0.1)
92 {
93 // Send stop drive command.
94 globals::g_pDriveBoard->SendStop();
95 // Update Idle start pose.
96 m_stStartRoverPose = stCurrentRoverPose;
97 // Submit logger message.
98 LOG_INFO(logging::g_qSharedLogger, "IdleState: Stopped drive.");
99 }
100
101 // If the last state was searchpattern and the waypoint handler has been cleared, reset.
102 if (globals::g_pStateMachineHandler->GetPreviousState() != States::eIdle && globals::g_pWaypointHandler->GetWaypointCount() <= 0)
103 {
104 // Submit logger message.
105 LOG_NOTICE(logging::g_qSharedLogger, "IdleState: WaypointHandler queue is empty while in IdleState, deleting old saved states...");
106 // Reset all old states. Since waypoint handler has been cleared, there's no need to save old searchpattern state.
107 globals::g_pStateMachineHandler->ClearSavedStates();
108 }
109 }
void SendStop()
Stop the drivetrain of the Rover.
Definition DriveBoard.cpp:163
void ClearSavedStates()
Clear all saved states.
Definition StateMachineHandler.cpp:376
geoops::RoverPose SmartRetrieveRoverPose(bool bVIOHeading=true, bool bVIOTracking=false)
Retrieve the rover's current position and heading. Automatically picks between getting the position/h...
Definition WaypointHandler.cpp:742
GeoMeasurement CalculateGeoMeasurement(const GPSCoordinate &stCoord1, const GPSCoordinate &stCoord2)
The shortest path between two points on an ellipsoid at (lat1, lon1) and (lat2, lon2) is called the g...
Definition GeospatialOperations.hpp:522
This struct is used to store the distance, arc length, and relative bearing for a calculated geodesic...
Definition GeospatialOperations.hpp:82
This struct is used by the WaypointHandler to provide an easy way to store all pose data about the ro...
Definition GeospatialOperations.hpp:677
const geoops::GPSCoordinate & GetGPSCoordinate() const
Accessor for the geoops::GPSCoordinate member variable.
Definition GeospatialOperations.hpp:725
Here is the call graph for this function:

◆ TriggerEvent()

States statemachine::IdleState::TriggerEvent ( Event  eEvent)
overridevirtual

Trigger an event in the state machine. Returns the next state.

Parameters
eEvent- The event to trigger.
Returns
std::shared_ptr<State> - The next state.
Author
Eli Byrd (edbgk.nosp@m.k@ms.nosp@m.t.edu)
Date
2024-01-17

Implements statemachine::State.

121 {
122 // Create instance variables.
123 States eNextState = States::eIdle;
124 bool bCompleteStateExit = true;
125
126 switch (eEvent)
127 {
128 case Event::eStart:
129 {
130 // Submit logger message.
131 LOG_INFO(logging::g_qSharedLogger, "IdleState: Handling Start event.");
132 // Send multimedia command to update state display.
133 globals::g_pMultimediaBoard->SendLightingState(MultimediaBoard::MultimediaBoardLightingState::eAutonomy);
134
135 bool tagInSight = false; // TODO: Replace with actual tag detection
136 bool reverseAlways = false; // TODO: Replace with actual reverse always flag
137
138 // If there is an ArUco marker in the camera's field of view, transition to backup before navigating.
139 if (tagInSight)
140 {
141 LOG_INFO(logging::g_qSharedLogger, "IdleState: Detected ArUco marker. Transitioning to Reverse State.");
142 eNextState = States::eReversing;
143 }
144 // If the reverse always flag is set, transition to backup before navigating.
145 else if (reverseAlways)
146 {
147 LOG_INFO(logging::g_qSharedLogger, "IdleState: Reverse always flag set. Transitioning to Reverse State.");
148 eNextState = States::eReversing;
149 }
150 // Otherwise, transition to navigating.
151 else
152 {
153 // Check if waypoint handler has any waypoints.
154 if (globals::g_pWaypointHandler->GetWaypointCount() > 0)
155 {
156 // Submit logger message.
157 LOG_INFO(logging::g_qSharedLogger, "IdleState: No ArUco marker detected. Transitioning to Navigating State.");
158 // Change states.
159 eNextState = States::eNavigating;
160 }
161 else
162 {
163 // Submit logger message.
164 LOG_NOTICE(logging::g_qSharedLogger,
165 "IdleState: Not transitioning to NavigatingState because no waypoints have been added to the waypoint handler!");
166 }
167 }
168
169 break;
170 }
171 case Event::eAbort:
172 {
173 // Submit logger message.
174 LOG_INFO(logging::g_qSharedLogger, "IdleState: Handling Abort event.");
175 // Send multimedia command to update state display.
176 globals::g_pMultimediaBoard->SendLightingState(MultimediaBoard::MultimediaBoardLightingState::eOff);
177 // Ensure drive is stopped.
178 globals::g_pDriveBoard->SendStop();
179 break;
180 }
181 default:
182 {
183 // Submit logger message.
184 LOG_WARNING(logging::g_qSharedLogger, "IdleState: Handling unknown event.");
185 break;
186 }
187 }
188
189 if (eNextState != States::eIdle)
190 {
191 LOG_INFO(logging::g_qSharedLogger, "IdleState: Transitioning to {} State.", StateToString(eNextState));
192
193 // Exit the current state
194 if (bCompleteStateExit)
195 {
196 Exit();
197 }
198 }
199
200 return eNextState;
201 }
void SendLightingState(MultimediaBoardLightingState eState)
Sends a predetermined color pattern to board.
Definition MultimediaBoard.cpp:55
void Exit() override
This method is called when the state is exited. It is used to clean up the state.
Definition IdleState.cpp:48
std::string StateToString(States eState)
Converts a state object to a string.
Definition State.hpp:89
States
The states that the state machine can be in.
Definition State.hpp:31
Here is the call graph for this function:

The documentation for this class was generated from the following files: