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
ObjectDetector.h
Go to the documentation of this file.
1
11#ifndef OBJECT_DETECTOR_H
12#define OBJECT_DETECTOR_H
13
14#include "../../interfaces/BasicCamera.hpp"
15#include "../../interfaces/ZEDCamera.hpp"
16#include "../../util/vision/ObjectDetectionUtility.hpp"
17#include "../../util/vision/YOLOModel.hpp"
18
20#include <future>
21#include <shared_mutex>
22#include <vector>
23
25
26
36class ObjectDetector : public AutonomyThread<void>
37{
38 public:
40 // Declare public methods and member variables.
42 ObjectDetector(std::shared_ptr<BasicCamera> pBasicCam,
43 const bool bEnableTracking = false,
44 const int nDetectorMaxFPS = 30,
45 const bool bEnableRecordingFlag = false,
46 const int nNumDetectedObjectsRetrievalThreads = 5,
47 const bool bUsingGpuMats = false);
48 ObjectDetector(std::shared_ptr<ZEDCamera> pZEDCam,
49 const bool bEnableTracking = false,
50 const int nDetectorMaxFPS = 30,
51 const bool bEnableRecordingFlag = false,
52 const int nNumDetectedObjectsRetrievalThreads = 5,
53 const bool bUsingGpuMats = false);
55 std::future<bool> RequestDetectionOverlayFrame(cv::Mat& cvFrame);
56 std::future<bool> RequestDetectedObjects(std::vector<objectdetectutils::Object>& vObjects);
57 bool InitTorchDetection(const std::string& szModelPath,
58 yolomodel::pytorch::PyTorchInterpreter::HardwareDevices eDevice = yolomodel::pytorch::PyTorchInterpreter::HardwareDevices::eCUDA);
59
61 // Mutators.
63
64 void EnableTorchDetection(const float fMinObjectConfidence = 0.4f, const float fNMSThreshold = 0.6f);
66 void SetDetectorMaxFPS(const int nRecordingFPS);
67 void SetEnableRecordingFlag(const bool bEnableRecordingFlag);
68
70 // Accessors.
72
73 bool GetIsReady();
74 int GetDetectorMaxFPS() const;
75 bool GetEnableRecordingFlag() const;
76 std::string GetCameraName();
78
79 private:
81 // Declare private methods.
83
84 void ThreadedContinuousCode() override;
85 void PooledLinearCode() override;
86 void UpdateDetectedObjects(std::vector<objectdetectutils::Object>& vNewlyDetectedObjects);
87
89 // Declare private member variables.
91 // Class member variables.
92
93 std::shared_ptr<Camera<cv::Mat>> m_pCamera;
94 std::shared_ptr<yolomodel::pytorch::PyTorchInterpreter> m_pTorchDetector;
95 std::atomic<float> m_fTorchMinObjectConfidence;
96 std::atomic<float> m_fTorchNMSThreshold;
97 std::atomic_bool m_bTorchInitialized;
98 std::atomic_bool m_bTorchEnabled;
99 std::shared_ptr<tracking::MultiTracker> m_pMultiTracker;
100 bool m_bUsingZedCamera;
101 bool m_bUsingGpuMats;
102 bool m_bCameraIsOpened;
103 bool m_bEnableTracking;
104 int m_nNumDetectedObjectsRetrievalThreads;
105 std::string m_szCameraName;
106 std::atomic_bool m_bEnableRecordingFlag;
107
108 // Detected tags storage.
109
110 std::vector<objectdetectutils::Object> m_vNewlyDetectedObjects;
111 std::vector<objectdetectutils::Object> m_vDetectedObjects;
112
113 // Rover position for tag geolocalization.
114 geoops::RoverPose m_stRoverPose;
115
116 // Create frames for storing images and point clouds.
117
118 cv::Mat m_cvFrame;
119 cv::cuda::GpuMat m_cvGPUFrame;
120 cv::Mat m_cvTorchOverlayFrame;
121 cv::Mat m_cvTorchProcFrame;
122 cv::Mat m_cvPointCloud;
123 cv::cuda::GpuMat m_cvGPUPointCloud;
124
125 // Queues and mutexes for scheduling and copying data to other threads.
126
127 std::queue<containers::FrameFetchContainer<cv::Mat>> m_qDetectedObjectDrawnOverlayFramesCopySchedule;
128 std::queue<containers::DataFetchContainer<std::vector<objectdetectutils::Object>>> m_qDetectedObjectCopySchedule;
129 std::shared_mutex m_muPoolScheduleMutex;
130 std::shared_mutex m_muFrameCopyMutex;
131 std::shared_mutex m_muArucoDataCopyMutex;
132};
133
134#endif
Interface class used to easily multithread a child class.
Definition AutonomyThread.hpp:38
This class implements a modular and easy to use object detector for a single camera....
Definition ObjectDetector.h:37
std::future< bool > RequestDetectionOverlayFrame(cv::Mat &cvFrame)
Request a copy of the frame containing the detected objects from all detection methods drawn onto the...
Definition ObjectDetector.cpp:393
void SetEnableRecordingFlag(const bool bEnableRecordingFlag)
Set the flag to enable or disable recording of the overlay output.
Definition ObjectDetector.cpp:535
bool GetEnableRecordingFlag() const
Get the flag to enable or disable recording of the overlay output.
Definition ObjectDetector.cpp:606
void UpdateDetectedObjects(std::vector< objectdetectutils::Object > &vNewlyDetectedObjects)
Update the detected objects with the newly detected objects.
Definition ObjectDetector.cpp:657
void PooledLinearCode() override
This method will run in a thread pool. It will be called by the main thread and will run the code wit...
Definition ObjectDetector.cpp:332
void EnableTorchDetection(const float fMinObjectConfidence=0.4f, const float fNMSThreshold=0.6f)
Enable the PyTorch detection method for this ObjectDetector.
Definition ObjectDetector.cpp:479
std::string GetCameraName()
Get the camera name.
Definition ObjectDetector.cpp:620
void DisableTorchDetection()
Set the flag to enable or disable object detection with the torch model.
Definition ObjectDetector.cpp:507
int GetDetectorMaxFPS() const
Get the max FPS of the detector.
Definition ObjectDetector.cpp:591
std::future< bool > RequestDetectedObjects(std::vector< objectdetectutils::Object > &vObjects)
Request a copy of the most update to date vector of the detected objects from all detection methods.
Definition ObjectDetector.cpp:419
bool GetIsReady()
Check if the ObjectDetector is ready to be used.
Definition ObjectDetector.cpp:550
bool InitTorchDetection(const std::string &szModelPath, yolomodel::pytorch::PyTorchInterpreter::HardwareDevices eDevice=yolomodel::pytorch::PyTorchInterpreter::HardwareDevices::eCUDA)
Initialize the PyTorch interpreter for object detection.
Definition ObjectDetector.cpp:446
~ObjectDetector()
Destroy the Object Detector:: Object Detector object.
Definition ObjectDetector.cpp:121
cv::Size GetProcessFrameResolution() const
Get the process frame resolution.
Definition ObjectDetector.cpp:634
void SetDetectorMaxFPS(const int nRecordingFPS)
Set the max FPS of the detector.
Definition ObjectDetector.cpp:521
void ThreadedContinuousCode() override
This method will run continuously in a separate thread. New frames from the given camera are grabbed ...
Definition ObjectDetector.cpp:142
This struct is used by the WaypointHandler to provide an easy way to store all pose data about the ro...
Definition GeospatialOperations.hpp:677