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
StateMachineHandler.h
Go to the documentation of this file.
1
11#ifndef STATEMACHINEHANDLER_H
12#define STATEMACHINEHANDLER_H
13
14#include "../states/ApproachingMarkerState.h"
15#include "../states/ApproachingObjectState.h"
16#include "../states/IdleState.h"
17#include "../states/NavigatingState.h"
18#include "../states/ReversingState.h"
19#include "../states/SearchPatternState.h"
20#include "../states/StuckState.h"
21#include "../states/VerifyingMarkerState.h"
22#include "../states/VerifyingObjectState.h"
23#include "../states/VerifyingPositionState.h"
24#include "./CameraHandler.h"
25
27#include <RoveComm/RoveComm.h>
28#include <RoveComm/RoveCommManifest.h>
29#include <atomic>
30#include <shared_mutex>
31
33
34
44{
45 private:
47 // Declare private class member variables.
49 std::shared_ptr<statemachine::State> m_pCurrentState;
50 std::shared_ptr<statemachine::State> m_pPreviousState;
51 std::unordered_map<statemachine::States, std::shared_ptr<statemachine::State>> m_umSavedStates;
52 std::shared_mutex m_muStateMutex;
53 std::shared_mutex m_muEventMutex;
54 std::atomic_bool m_bSwitchingStates;
55 std::shared_ptr<ZEDCamera> m_pMainCam;
56 geoops::GPSCoordinate m_stCurrentGPSLocation;
57
59 // Declare private class methods.
61 std::shared_ptr<statemachine::State> CreateState(statemachine::States eState);
62 void ChangeState(statemachine::States eNextState, const bool bSaveCurrentState = false);
63 void SaveCurrentState();
64 void ThreadedContinuousCode() override;
65 void PooledLinearCode() override;
66
67
75 const std::function<void(const rovecomm::RoveCommPacket<uint8_t>&, const sockaddr_in&)> AutonomyStartCallback =
76 [this](const rovecomm::RoveCommPacket<uint8_t>& stPacket, const sockaddr_in& stdAddr)
77 {
78 // Not using this.
79 (void) stPacket;
80 (void) stdAddr;
81
82 // Submit logger message.
83 LOG_INFO(logging::g_qSharedLogger, "Incoming Packet: Start Autonomy!");
84
85 // Signal statemachine handler with Start event.
86 this->HandleEvent(statemachine::Event::eStart);
87 };
88
89
97 const std::function<void(const rovecomm::RoveCommPacket<uint8_t>&, const sockaddr_in&)> AutonomyStopCallback =
98 [this](const rovecomm::RoveCommPacket<uint8_t>& stPacket, const sockaddr_in& stdAddr)
99 {
100 // Not using this.
101 (void) stPacket;
102 (void) stdAddr;
103
104 // Submit logger message.
105 LOG_INFO(logging::g_qSharedLogger, "Incoming Packet: Abort Autonomy!");
106
107 // Signal statemachine handler with stop event.
108 this->HandleEvent(statemachine::Event::eAbort, true);
109 };
110
111
118 const std::function<void(const rovecomm::RoveCommPacket<uint8_t>&, const sockaddr_in&)> ClearWaypointsCallback =
119 [this](const rovecomm::RoveCommPacket<uint8_t>& stPacket, const sockaddr_in& stdAddr)
120 {
121 // Not using this.
122 (void) stPacket;
123 (void) stdAddr;
124
125 /*
126 The clear waypoints command will clear all waypoints in the WaypointHandler, but it also clears all saved states in the StateMachineHandler
127 to prevent any conflicts when restarting autonomy with previously saved states that may have waypoints associated with them.
128 However, we only want to delete our saved states if we are currently in IdleState.
129 */
130
131 // Check if the current state is IdleState.
132 if (this->GetCurrentState() == statemachine::States::eIdle)
133 {
134 // Submit logger message.
135 LOG_NOTICE(logging::g_qSharedLogger, "Incoming Clear Waypoints packet: Deleting all saved states in StateMachineHandler...");
136 // Clear the saved states.
137 this->ClearSavedStates();
138 }
139 else
140 {
141 // Submit logger message.
142 LOG_WARNING(logging::g_qSharedLogger,
143 "Incoming Clear Waypoints packet: Cannot clear saved states in StateMachineHandler unless in Idle state. Current state is {}.",
144 static_cast<int>(this->GetCurrentState()));
145 }
146 };
147
148
156 const std::function<void(const rovecomm::RoveCommPacket<float>&, const sockaddr_in&)> PMSCellVoltageCallback =
157 [this](const rovecomm::RoveCommPacket<float>& stPacket, const sockaddr_in& stdAddr)
158 {
159 // Not using this.
160 (void) stdAddr;
161
162 // Create instance variables.
163 double dTotalCellVoltages = 0.0;
164 int nValidCellVoltageValues = 0;
165
166 // Loop through voltage values and average all of the valid ones.
167 for (int nIter = 0; nIter < stPacket.unDataCount; ++nIter)
168 {
169 // Check if the voltage values is greater than at least 0.1.
170 if (stPacket.vData[nIter] >= 0.1)
171 {
172 // Add cell voltage value to total.
173 dTotalCellVoltages += stPacket.vData[nIter];
174 // Increment voltage voltage counter.
175 ++nValidCellVoltageValues;
176 }
177 }
178 // Calculate average cell voltage.
179 double dAverageCellVoltage = dTotalCellVoltages / nValidCellVoltageValues;
180
181 // Submit logger message.
182 LOG_DEBUG(logging::g_qSharedLogger, "Incoming Packet: PMS Cell Voltages. Average voltage is: {}", dAverageCellVoltage);
183
184 // Check if voltage is above the safe minimum for lithium ion batteries.
185 if (constants::BATTERY_CHECKS_ENABLED && dAverageCellVoltage < constants::BATTERY_MINIMUM_CELL_VOLTAGE &&
186 this->GetCurrentState() != statemachine::States::eIdle)
187 {
188 // Submit logger message.
189 LOG_CRITICAL(logging::g_qSharedLogger,
190 "Incoming PMS Packet: Average cell voltage is {} which is below the safe minimum of {}. Entering Idle state...",
191 dAverageCellVoltage,
192 constants::BATTERY_MINIMUM_CELL_VOLTAGE);
193
194 // Signal statemachine handler with stop event.
195 this->HandleEvent(statemachine::Event::eAbort, true);
196 }
197 };
198
199 public:
201 // Declare public class methods and variables.
205 void StartStateMachine();
206 void StopStateMachine();
207 void HandleEvent(statemachine::Event eEvent, const bool bSaveCurrentState = false);
208 void ClearSavedStates();
212
213 // Smart location retrieving.
214 geoops::RoverPose SmartRetrieveRoverPose(bool bVIOHeading = true, bool bVIOTracking = false);
215 double SmartRetrieveVelocity();
217 void RealignZEDPosition(CameraHandler::ZEDCamName eCameraName, const geoops::UTMCoordinate& stNewCameraPosition, const double dNewCameraHeading);
218
220};
221
222#endif // STATEMACHINEHANDLER_H
Defines the CameraHandler class.
Interface class used to easily multithread a child class.
Definition AutonomyThread.hpp:38
IPS & GetIPS()
Accessor for the Frame I P S private member.
Definition AutonomyThread.hpp:224
The StateMachineHandler class serves as the main state machine for Autonomy Software....
Definition StateMachineHandler.h:44
void StartStateMachine()
This method will start the state machine. It will set the first state to Idle and start the thread po...
Definition StateMachineHandler.cpp:187
void ClearSavedState(statemachine::States eState)
Clear a saved state based on the given state.
Definition StateMachineHandler.cpp:397
const std::function< void(const rovecomm::RoveCommPacket< uint8_t > &, const sockaddr_in &)> AutonomyStartCallback
Callback function used to trigger the start of autonomy. No matter what state we are in,...
Definition StateMachineHandler.h:75
double SmartRetrieveAngularVelocity()
Retrieve the rover's current velocity. Currently there is no easy way to get the velocity of the ZEDC...
Definition StateMachineHandler.cpp:628
void ClearSavedStates()
Clear all saved states.
Definition StateMachineHandler.cpp:379
statemachine::States GetCurrentState() const
Accessor for the Current State private member.
Definition StateMachineHandler.cpp:413
const std::function< void(const rovecomm::RoveCommPacket< float > &, const sockaddr_in &)> PMSCellVoltageCallback
Callback function used to force autonomy into Idle state if battery voltage gets too low....
Definition StateMachineHandler.h:156
void PooledLinearCode() override
This method holds the code that is ran in the thread pool started by the ThreadedLinearCode() method....
Definition StateMachineHandler.cpp:337
std::shared_ptr< statemachine::State > CreateState(statemachine::States eState)
Create a State object based of of the State enum.
Definition StateMachineHandler.cpp:75
double SmartRetrieveVelocity()
Retrieve the rover's current velocity. Currently there is no easy way to get the velocity of the ZEDC...
Definition StateMachineHandler.cpp:612
void RealignZEDPosition(CameraHandler::ZEDCamName eCameraName, const geoops::UTMCoordinate &stNewCameraPosition, const double dNewCameraHeading)
This is used to realign the ZEDs forward direction with the rover's current compass heading....
Definition StateMachineHandler.cpp:648
const std::function< void(const rovecomm::RoveCommPacket< uint8_t > &, const sockaddr_in &)> AutonomyStopCallback
Callback function used to trigger autonomy to stop. No matter what state we are in,...
Definition StateMachineHandler.h:97
void ThreadedContinuousCode() override
This code will run continuously in a separate thread. The State Machine Handler will check the curren...
Definition StateMachineHandler.cpp:239
StateMachineHandler()
Construct a new State Machine Handler object.
Definition StateMachineHandler.cpp:23
const std::function< void(const rovecomm::RoveCommPacket< uint8_t > &, const sockaddr_in &)> ClearWaypointsCallback
Callback function that is called whenever RoveComm receives new CLEARWAYPOINTS packet.
Definition StateMachineHandler.h:118
statemachine::States GetPreviousState() const
Accessor for the Previous State private member.
Definition StateMachineHandler.cpp:426
~StateMachineHandler()
Destroy the State Machine Handler:: State Machine Handler object.
Definition StateMachineHandler.cpp:56
void StopStateMachine()
This method will stop the state machine. It will signal whatever state is currently running to abort ...
Definition StateMachineHandler.cpp:212
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 StateMachineHandler.cpp:445
void HandleEvent(statemachine::Event eEvent, const bool bSaveCurrentState=false)
This method Handles Events that are passed to the State Machine Handler. It will check the current st...
Definition StateMachineHandler.cpp:353
void ChangeState(statemachine::States eNextState, const bool bSaveCurrentState=false)
Transition to a new state. This function is called by the HandleEvent and checks to see if this state...
Definition StateMachineHandler.cpp:110
void SaveCurrentState()
Save the current state to the map of exited states. This is used to store the state when the state ma...
Definition StateMachineHandler.cpp:172
Event
The events that can be triggered in the state machine.
Definition State.hpp:52
States
The states that the state machine can be in.
Definition State.hpp:31
This struct stores/contains information about a GPS data.
Definition GeospatialOperations.hpp:100
This struct is used by the WaypointHandler to provide an easy way to store all pose data about the ro...
Definition GeospatialOperations.hpp:708
This struct stores/contains information about a UTM coordinate.
Definition GeospatialOperations.hpp:211