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 Class Reference

This class implements a modular and easy to use object detector for a single camera. Given a camera name, this class will detect objects using the depth measure from a ZED camera and/or inferenced objects from a custom trained model. This class and it's detections are ran in a different thread. More...

#include <ObjectDetector.h>

Inheritance diagram for ObjectDetector:
Collaboration diagram for ObjectDetector:

Public Member Functions

 ObjectDetector (std::shared_ptr< BasicCamera > pBasicCam, const bool bEnableTracking=false, const int nDetectorMaxFPS=30, const bool bEnableRecordingFlag=false, const int nNumDetectedObjectsRetrievalThreads=5, const bool bUsingGpuMats=false)
 Construct a new Object Detector:: Object Detector object.
 
 ObjectDetector (std::shared_ptr< ZEDCamera > pZEDCam, const bool bEnableTracking=false, const int nDetectorMaxFPS=30, const bool bEnableRecordingFlag=false, const int nNumDetectedObjectsRetrievalThreads=5, const bool bUsingGpuMats=false)
 Construct a new Object Detector:: Object Detector object.
 
 ~ObjectDetector ()
 Destroy the Object Detector:: Object Detector object.
 
std::future< bool > RequestDetectionOverlayFrame (cv::Mat &cvFrame)
 Request a copy of the frame containing the detected objects from all detection methods drawn onto the frame.
 
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.
 
bool InitTorchDetection (const std::string &szModelPath, yolomodel::pytorch::PyTorchInterpreter::HardwareDevices eDevice=yolomodel::pytorch::PyTorchInterpreter::HardwareDevices::eCUDA)
 Initialize the PyTorch interpreter for object detection.
 
void EnableTorchDetection (const float fMinObjectConfidence=0.4f, const float fNMSThreshold=0.6f)
 Enable the PyTorch detection method for this ObjectDetector.
 
void DisableTorchDetection ()
 Set the flag to enable or disable object detection with the torch model.
 
void SetDetectorMaxFPS (const int nRecordingFPS)
 Set the max FPS of the detector.
 
void SetEnableRecordingFlag (const bool bEnableRecordingFlag)
 Set the flag to enable or disable recording of the overlay output.
 
bool GetIsReady ()
 Check if the ObjectDetector is ready to be used.
 
int GetDetectorMaxFPS () const
 Get the max FPS of the detector.
 
bool GetEnableRecordingFlag () const
 Get the flag to enable or disable recording of the overlay output.
 
std::string GetCameraName ()
 Get the camera name.
 
cv::Size GetProcessFrameResolution () const
 Get the process frame resolution.
 
- Public Member Functions inherited from AutonomyThread< void >
 AutonomyThread ()
 Construct a new Autonomy Thread object.
 
virtual ~AutonomyThread ()
 Destroy the Autonomy Thread object. If the parent object or main thread is destroyed or exited while this thread is still running, a race condition will occur. Stopping and joining the thread here insures that the main program can't exit if the user forgot to stop and join the thread.
 
void Start ()
 When this method is called, it starts a new thread that runs the code within the ThreadedContinuousCode method. This is the users main code that will run the important and continuous code for the class.
 
void RequestStop ()
 Signals threads to stop executing user code, terminate. DOES NOT JOIN. This method will not force the thread to exit, if the user code is not written properly and contains WHILE statement or any other long-executing or blocking code, then the thread will not exit until the next iteration.
 
void Join ()
 Waits for thread to finish executing and then closes thread. This method will block the calling code until thread is finished.
 
bool Joinable () const
 Check if the code within the thread and all pools created by it are finished executing and the thread is ready to be closed.
 
AutonomyThreadState GetThreadState () const
 Accessor for the Threads State private member.
 
IPSGetIPS ()
 Accessor for the Frame I P S private member.
 

Private Member Functions

void ThreadedContinuousCode () override
 This method will run continuously in a separate thread. New frames from the given camera are grabbed and the objects for the camera image are detected using the PyTorch interpreter. The detected objects are then filtered and stored. Then any requests for the current objects are fulfilled via a call and join of the thread pooled code.
 
void PooledLinearCode () override
 This method will run in a thread pool. It will be called by the main thread and will run the code within the PooledLinearCode() method. This is meant to be used as an internal utility of the child class to further improve parallelization.
 
void UpdateDetectedObjects (std::vector< objectdetectutils::Object > &vNewlyDetectedObjects)
 Update the detected objects with the newly detected objects.
 

Private Attributes

std::shared_ptr< Camera< cv::Mat > > m_pCamera
 
std::shared_ptr< yolomodel::pytorch::PyTorchInterpreterm_pTorchDetector
 
std::atomic< float > m_fTorchMinObjectConfidence
 
std::atomic< float > m_fTorchNMSThreshold
 
std::atomic_bool m_bTorchInitialized
 
std::atomic_bool m_bTorchEnabled
 
std::shared_ptr< tracking::MultiTrackerm_pMultiTracker
 
bool m_bUsingZedCamera
 
bool m_bUsingGpuMats
 
bool m_bCameraIsOpened
 
bool m_bEnableTracking
 
int m_nNumDetectedObjectsRetrievalThreads
 
std::string m_szCameraName
 
std::atomic_bool m_bEnableRecordingFlag
 
std::vector< objectdetectutils::Objectm_vNewlyDetectedObjects
 
std::vector< objectdetectutils::Objectm_vDetectedObjects
 
geoops::RoverPose m_stRoverPose
 
cv::Mat m_cvFrame
 
cv::cuda::GpuMat m_cvGPUFrame
 
cv::Mat m_cvTorchOverlayFrame
 
cv::Mat m_cvTorchProcFrame
 
cv::Mat m_cvPointCloud
 
cv::cuda::GpuMat m_cvGPUPointCloud
 
std::queue< containers::FrameFetchContainer< cv::Mat > > m_qDetectedObjectDrawnOverlayFramesCopySchedule
 
std::queue< containers::DataFetchContainer< std::vector< objectdetectutils::Object > > > m_qDetectedObjectCopySchedule
 
std::shared_mutex m_muPoolScheduleMutex
 
std::shared_mutex m_muFrameCopyMutex
 
std::shared_mutex m_muArucoDataCopyMutex
 

Additional Inherited Members

- Public Types inherited from AutonomyThread< void >
enum  AutonomyThreadState
 
- Protected Member Functions inherited from AutonomyThread< void >
void RunPool (const unsigned int nNumTasksToQueue, const unsigned int nNumThreads=2, const bool bForceStopCurrentThreads=false)
 When this method is called, it starts/adds tasks to a thread pool that runs nNumTasksToQueue copies of the code within the PooledLinearCode() method using nNumThreads number of threads. This is meant to be used as an internal utility of the child class to further improve parallelization. Default value for nNumThreads is 2.
 
void RunDetachedPool (const unsigned int nNumTasksToQueue, const unsigned int nNumThreads=2, const bool bForceStopCurrentThreads=false)
 When this method is called, it starts a thread pool full of threads that don't return std::futures (like a placeholder for the thread return type). This means the thread will not have a return type and there is no way to determine if the thread has finished other than calling the Join() method. Only use this if you want to 'set and forget'. It will be faster as it doesn't return futures. Runs PooledLinearCode() method code. This is meant to be used as an internal utility of the child class to further improve parallelization.
 
void ParallelizeLoop (const int nNumThreads, const N tTotalIterations, F &&tLoopFunction)
 Given a ref-qualified looping function and an arbitrary number of iterations, this method will divide up the loop and run each section in a thread pool. This function must not return anything. This method will block until the loop has completed.
 
void ClearPoolQueue ()
 Clears any tasks waiting to be ran in the queue, tasks currently running will remain running.
 
void JoinPool ()
 Waits for pool to finish executing tasks. This method will block the calling code until thread is finished.
 
bool PoolJoinable () const
 Check if the internal pool threads are done executing code and the queue is empty.
 
void SetMainThreadIPSLimit (int nMaxIterationsPerSecond=0)
 Mutator for the Main Thread Max I P S private member.
 
int GetPoolNumOfThreads ()
 Accessor for the Pool Num Of Threads private member.
 
int GetPoolQueueLength ()
 Accessor for the Pool Queue Size private member.
 
std::vector< void > GetPoolResults ()
 Accessor for the Pool Results private member. The action of getting results will destroy and remove them from this object. This method blocks if the thread is not finished, so no need to call JoinPool() before getting results.
 
int GetMainThreadMaxIPS () const
 Accessor for the Main Thread Max I P S private member.
 
- Protected Attributes inherited from AutonomyThread< void >
IPS m_IPS
 

Detailed Description

This class implements a modular and easy to use object detector for a single camera. Given a camera name, this class will detect objects using the depth measure from a ZED camera and/or inferenced objects from a custom trained model. This class and it's detections are ran in a different thread.

Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-24

Constructor & Destructor Documentation

◆ ObjectDetector() [1/2]

ObjectDetector::ObjectDetector ( std::shared_ptr< BasicCamera pBasicCam,
const bool  bEnableTracking = false,
const int  nDetectorMaxFPS = 30,
const bool  bEnableRecordingFlag = false,
const int  nNumDetectedObjectsRetrievalThreads = 5,
const bool  bUsingGpuMats = false 
)

Construct a new Object Detector:: Object Detector object.

Parameters
pBasicCam- A pointer to the BasicCam to use for detection.
bEnableTracking- Whether or not to enable tracking of detected objects.
nDetectorMaxFPS- The max FPS limit the detector can run at.
bEnableRecordingFlag- Whether or not this ObjectDetector's overlay output should be recorded.
nNumDetectedObjectsRetrievalThreads- The number of threads to use when fulfilling requests for the detected objects. Default is 5.
bUsingGpuMats- Whether or not the given camera name will be using GpuMats.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2025-05-05
42{
43 // Initialize member variables.
44 m_pCamera = pBasicCam;
45 m_bEnableTracking = bEnableTracking;
46 m_bUsingZedCamera = false; // Toggle ZED functions off.
47 m_bEnableRecordingFlag = bEnableRecordingFlag;
48 m_nNumDetectedObjectsRetrievalThreads = nNumDetectedObjectsRetrievalThreads;
49 m_bUsingGpuMats = bUsingGpuMats;
50 m_bTorchInitialized = false;
51 m_bTorchEnabled = false;
52 m_bCameraIsOpened = false;
53 m_szCameraName = pBasicCam->GetCameraLocation();
54 m_stRoverPose = geoops::RoverPose();
55
56 // Create a multi-tracker for tracking multiple objects from the torch detectors.
57 m_pMultiTracker = std::make_shared<tracking::MultiTracker>(constants::BBOX_TRACKER_LOST_TIMEOUT,
58 constants::BBOX_TRACKER_MAX_TRACK_TIME,
59 constants::BBOX_TRACKER_IOU_MATCH_THRESHOLD);
60
61 // Set max IPS of main thread.
62 this->SetMainThreadIPSLimit(nDetectorMaxFPS);
63
64 // Submit logger message.
65 LOG_INFO(logging::g_qSharedLogger, "ObjectDetector created for camera at path/index: {}", m_szCameraName);
66}
void SetMainThreadIPSLimit(int nMaxIterationsPerSecond=0)
Mutator for the Main Thread Max I P S private member.
Definition AutonomyThread.hpp:467
This struct is used by the WaypointHandler to provide an easy way to store all pose data about the ro...
Definition GeospatialOperations.hpp:677
Here is the call graph for this function:

◆ ObjectDetector() [2/2]

ObjectDetector::ObjectDetector ( std::shared_ptr< ZEDCamera pZEDCam,
const bool  bEnableTracking = false,
const int  nDetectorMaxFPS = 30,
const bool  bEnableRecordingFlag = false,
const int  nNumDetectedObjectsRetrievalThreads = 5,
const bool  bUsingGpuMats = false 
)

Construct a new Object Detector:: Object Detector object.

Parameters
pZEDCam- A pointer to the ZEDCamera to use for detection.
bEnableTracking- Whether or not to enable tracking of detected objects.
nDetectorMaxFPS- The max FPS limit the detector can run at.
bEnableRecordingFlag- Whether or not this ObjectDetector's overlay output should be recorded.
nNumDetectedObjectsRetrievalThreads- The number of threads to use when fulfilling requests for the detected objects. Default is 5.
bUsingGpuMats- Whether or not the given camera name will be using GpuMats.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2025-05-05
88{
89 // Initialize member variables.
90 m_pCamera = pZEDCam;
91 m_bEnableTracking = bEnableTracking;
92 m_bUsingZedCamera = true; // Toggle ZED functions on.
93 m_bEnableRecordingFlag = bEnableRecordingFlag;
94 m_nNumDetectedObjectsRetrievalThreads = nNumDetectedObjectsRetrievalThreads;
95 m_bUsingGpuMats = bUsingGpuMats;
96 m_bTorchInitialized = false;
97 m_bTorchEnabled = false;
98 m_bCameraIsOpened = false;
99 m_szCameraName = pZEDCam->GetCameraModel() + "_" + std::to_string(pZEDCam->GetCameraSerial());
100 m_stRoverPose = geoops::RoverPose();
101
102 // Create a multi-tracker for tracking multiple objects from the torch detectors.
103 m_pMultiTracker = std::make_shared<tracking::MultiTracker>(constants::BBOX_TRACKER_LOST_TIMEOUT,
104 constants::BBOX_TRACKER_IOU_MATCH_THRESHOLD,
105 constants::BBOX_TRACKER_IOU_MATCH_THRESHOLD);
106
107 // Set max IPS of main thread.
108 this->SetMainThreadIPSLimit(nDetectorMaxFPS);
109
110 // Submit logger message.
111 LOG_INFO(logging::g_qSharedLogger, "ObjectDetector created for camera: {}", m_szCameraName);
112}
Here is the call graph for this function:

◆ ~ObjectDetector()

ObjectDetector::~ObjectDetector ( )

Destroy the Object Detector:: Object Detector object.

Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2025-05-05
122{
123 // Stop threaded code.
124 this->RequestStop();
125 this->Join();
126
127 // Submit logger message.
128 LOG_INFO(logging::g_qSharedLogger, "ObjectDetector for camera {} has been destroyed.", this->GetCameraName());
129}
void Join()
Waits for thread to finish executing and then closes thread. This method will block the calling code ...
Definition AutonomyThread.hpp:180
void RequestStop()
Signals threads to stop executing user code, terminate. DOES NOT JOIN. This method will not force the...
Definition AutonomyThread.hpp:164
std::string GetCameraName()
Get the camera name.
Definition ObjectDetector.cpp:620
Here is the call graph for this function:

Member Function Documentation

◆ RequestDetectionOverlayFrame()

std::future< bool > ObjectDetector::RequestDetectionOverlayFrame ( cv::Mat cvFrame)

Request a copy of the frame containing the detected objects from all detection methods drawn onto the frame.

Parameters
cvFrame- The cv::Mat frame to copy the detection overlay image to.
Returns
std::future<bool> - The future that will be set to true when the frame is copied.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2025-05-05
394{
395 // Assemble the DataFetchContainer.
396 containers::FrameFetchContainer<cv::Mat> stContainer(cvFrame, PIXEL_FORMATS::eObjectDetection);
397
398 // Acquire lock on pool copy queue.
399 std::unique_lock<std::shared_mutex> lkScheduler(m_muPoolScheduleMutex);
400 // Append frame fetch container to the schedule queue.
401 m_qDetectedObjectDrawnOverlayFramesCopySchedule.push(stContainer);
402 // Release lock on the frame schedule queue.
403 lkScheduler.unlock();
404
405 // Return the future from the promise stored in the container.
406 return stContainer.pCopiedFrameStatus->get_future();
407}
This struct is used to carry references to camera frames for scheduling and copying....
Definition FetchContainers.hpp:89

◆ RequestDetectedObjects()

std::future< bool > ObjectDetector::RequestDetectedObjects ( std::vector< objectdetectutils::Object > &  vObjects)

Request a copy of the most update to date vector of the detected objects from all detection methods.

Parameters
vObjects- The vector of detected objects to copy the detected objects to.
Returns
std::future<bool> - The future that will be set to true when the objects are copied.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2025-05-05
420{
421 // Assemble the DataFetchContainer.
423
424 // Acquire lock on pool copy queue.
425 std::unique_lock<std::shared_mutex> lkScheduler(m_muPoolScheduleMutex);
426 // Append frame fetch container to the schedule queue.
427 m_qDetectedObjectCopySchedule.push(stContainer);
428 // Release lock on the frame schedule queue.
429 lkScheduler.unlock();
430
431 // Return the future from the promise stored in the container.
432 return stContainer.pCopiedDataStatus->get_future();
433}
This struct is used to carry references to any datatype for scheduling and copying....
Definition FetchContainers.hpp:165

◆ InitTorchDetection()

bool ObjectDetector::InitTorchDetection ( const std::string &  szModelPath,
yolomodel::pytorch::PyTorchInterpreter::HardwareDevices  eDevice = yolomodel::pytorch::PyTorchInterpreter::HardwareDevices::eCUDA 
)

Initialize the PyTorch interpreter for object detection.

Parameters
szModelPath- The path to the PyTorch model file.
eDevice- The hardware device to use for inference (e.g., CPU or GPU).
Returns
true - Model was opened and loaded successfully onto the torch device.
false - Model was not opened and loaded successfully onto the torch device.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2025-05-05
447{
448 // Initialize a new YOLOModel object.
449 m_pTorchDetector = std::make_shared<yolomodel::pytorch::PyTorchInterpreter>(szModelPath, eDevice);
450
451 // Check if device/model was opened without issue.
452 if (m_pTorchDetector->IsReadyForInference())
453 {
454 // Update member variable.
455 m_bTorchInitialized = true;
456 // Return status.
457 return true;
458 }
459 else
460 {
461 // Submit logger message.
462 LOG_ERROR(logging::g_qSharedLogger, "Unable to initialize Torch detection for ObjectDetector.");
463 // Update member variable.
464 m_bTorchInitialized = false;
465 // Return status.
466 return false;
467 }
468}

◆ EnableTorchDetection()

void ObjectDetector::EnableTorchDetection ( const float  fMinObjectConfidence = 0.4f,
const float  fNMSThreshold = 0.6f 
)

Enable the PyTorch detection method for this ObjectDetector.

Parameters
fMinObjectConfidence- The minimum confidence threshold for detected objects.
fNMSThreshold- The non-maximum suppression threshold for filtering overlapping detections.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2025-05-05
480{
481 // Update member variables.
482 m_fTorchMinObjectConfidence = fMinObjectConfidence;
483 m_fTorchNMSThreshold = fNMSThreshold;
484
485 // Check if torch model has been initialized.
486 if (m_bTorchInitialized)
487 {
488 // Update member variable.
489 m_bTorchEnabled = true;
490 }
491 else
492 {
493 // Submit logger message.
494 LOG_WARNING(logging::g_qSharedLogger, "Tried to enable torch detection for ObjectDetector but it has not been initialized yet!");
495 // Update member variable.
496 m_bTorchEnabled = false;
497 }
498}

◆ DisableTorchDetection()

void ObjectDetector::DisableTorchDetection ( )

Set the flag to enable or disable object detection with the torch model.

Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2025-05-05
508{
509 // Update member variable.
510 m_bTorchEnabled = false;
511}

◆ SetDetectorMaxFPS()

void ObjectDetector::SetDetectorMaxFPS ( const int  nRecordingFPS)

Set the max FPS of the detector.

Parameters
nRecordingFPS- The max FPS of the detector.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2025-05-05
522{
523 // Set the max iterations per second of the main thread.
524 this->SetMainThreadIPSLimit(nRecordingFPS);
525}
Here is the call graph for this function:

◆ SetEnableRecordingFlag()

void ObjectDetector::SetEnableRecordingFlag ( const bool  bEnableRecordingFlag)

Set the flag to enable or disable recording of the overlay output.

Parameters
bEnableRecordingFlag- The flag to enable or disable recording of the overlay output.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2025-05-05
536{
537 // Update member variable.
538 m_bEnableRecordingFlag = bEnableRecordingFlag;
539}

◆ GetIsReady()

bool ObjectDetector::GetIsReady ( )

Check if the ObjectDetector is ready to be used.

Returns
true - The ObjectDetector is ready to be used.
false - The ObjectDetector is not ready to be used.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2025-05-05
551{
552 // Create instance variables.
553 bool bDetectorIsReady = false;
554
555 // Check if this detectors thread is currently running.
556 if (this->GetThreadState() == AutonomyThreadState::eRunning)
557 {
558 // Check if using ZEDCam or BasicCam.
559 if (m_bUsingZedCamera)
560 {
561 // Check if camera is NOT open.
562 if (std::dynamic_pointer_cast<ZEDCamera>(m_pCamera)->GetCameraIsOpen())
563 {
564 // Set camera opened toggle.
565 bDetectorIsReady = true;
566 }
567 }
568 else
569 {
570 // Check if camera is NOT open.
571 if (std::dynamic_pointer_cast<BasicCamera>(m_pCamera)->GetCameraIsOpen())
572 {
573 // Set camera opened toggle.
574 bDetectorIsReady = true;
575 }
576 }
577 }
578
579 // Return if this detector is ready or not.
580 return bDetectorIsReady;
581}
AutonomyThreadState GetThreadState() const
Accessor for the Threads State private member.
Definition AutonomyThread.hpp:214
Here is the call graph for this function:

◆ GetDetectorMaxFPS()

int ObjectDetector::GetDetectorMaxFPS ( ) const

Get the max FPS of the detector.

Returns
int - The max FPS of the detector.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2025-05-05
592{
593 // Return the max FPS of the detector.
594 return this->GetMainThreadMaxIPS();
595}
int GetMainThreadMaxIPS() const
Accessor for the Main Thread Max I P S private member.
Definition AutonomyThread.hpp:531
Here is the call graph for this function:

◆ GetEnableRecordingFlag()

bool ObjectDetector::GetEnableRecordingFlag ( ) const

Get the flag to enable or disable recording of the overlay output.

Returns
true - The flag to enable or disable recording of the overlay output.
false - The flag to enable or disable recording of the overlay output.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2025-05-05
607{
608 // Return the enable recording flag.
609 return m_bEnableRecordingFlag;
610}

◆ GetCameraName()

std::string ObjectDetector::GetCameraName ( )

Get the camera name.

Returns
std::string - The camera name.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2025-05-05
621{
622 // Return the camera name.
623 return m_szCameraName;
624}
Here is the caller graph for this function:

◆ GetProcessFrameResolution()

cv::Size ObjectDetector::GetProcessFrameResolution ( ) const

Get the process frame resolution.

Returns
cv::Size - The process frame resolution.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2025-05-05
635{
636 // Check if using a ZED camera.
637 if (m_bUsingZedCamera)
638 {
639 // Concatenate camera model name and serial number.
640 return std::dynamic_pointer_cast<ZEDCamera>(m_pCamera)->GetPropResolution();
641 }
642 else
643 {
644 // Concatenate camera path or index.
645 return std::dynamic_pointer_cast<BasicCamera>(m_pCamera)->GetPropResolution();
646 }
647}

◆ ThreadedContinuousCode()

void ObjectDetector::ThreadedContinuousCode ( )
overrideprivatevirtual

This method will run continuously in a separate thread. New frames from the given camera are grabbed and the objects for the camera image are detected using the PyTorch interpreter. The detected objects are then filtered and stored. Then any requests for the current objects are fulfilled via a call and join of the thread pooled code.

Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2025-05-05

Implements AutonomyThread< void >.

143{
144 // Check if using ZEDCam or BasicCam.
145 if (m_bUsingZedCamera)
146 {
147 // Check if camera is NOT open.
148 if (!std::dynamic_pointer_cast<ZEDCamera>(m_pCamera)->GetCameraIsOpen())
149 {
150 // Set camera opened toggle.
151 m_bCameraIsOpened = false;
152
153 // If camera's not open on first iteration of thread, it's probably not present, so stop.
154 if (this->GetThreadState() == AutonomyThreadState::eStarting)
155 {
156 // Shutdown threads for this ZEDCam.
157 this->RequestStop();
158
159 // Submit logger message.
160 LOG_CRITICAL(logging::g_qSharedLogger,
161 "ObjectDetector start was attempted for ZED camera with serial number {}, but camera never properly opened or it has been closed/rebooted! "
162 "This object detector will now stop.",
163 std::dynamic_pointer_cast<ZEDCamera>(m_pCamera)->GetCameraSerial());
164 }
165 }
166 else
167 {
168 // Set camera opened toggle.
169 m_bCameraIsOpened = true;
170 }
171 }
172 else
173 {
174 // Check if camera is NOT open.
175 if (!std::dynamic_pointer_cast<BasicCamera>(m_pCamera)->GetCameraIsOpen())
176 {
177 // Set camera opened toggle.
178 m_bCameraIsOpened = false;
179
180 // If camera's not open on first iteration of thread, it's probably not present, so stop.
181 if (this->GetThreadState() == AutonomyThreadState::eStarting)
182 {
183 // Shutdown threads for this BasicCam.
184 this->RequestStop();
185
186 // Submit logger message.
187 LOG_CRITICAL(logging::g_qSharedLogger,
188 "ObjectDetector start was attempted for BasicCam at {}, but camera never properly opened or it has become disconnected!",
189 std::dynamic_pointer_cast<BasicCamera>(m_pCamera)->GetCameraLocation());
190 }
191 }
192 else
193 {
194 // Set camera opened toggle.
195 m_bCameraIsOpened = true;
196 }
197 }
198
199 // Check if camera is opened.
200 if (m_bCameraIsOpened)
201 {
202 // Create future for indicating when the frame has been copied.
203 std::future<bool> fuPointCloudCopyStatus;
204 std::future<bool> fuRegularFrameCopyStatus;
205
206 // Check if the camera is setup to use CPU or GPU mats.
207 if (m_bUsingZedCamera)
208 {
209 // Check if the ZED camera is returning cv::cuda::GpuMat or cv:Mat.
210 if (m_bUsingGpuMats)
211 {
212 // Grabs point cloud from ZEDCam. Dynamic casts Camera to ZEDCamera* so we can use ZEDCam methods.
213 fuPointCloudCopyStatus = std::dynamic_pointer_cast<ZEDCamera>(m_pCamera)->RequestPointCloudCopy(m_cvGPUPointCloud);
214 // Get the regular RGB image from the camera.
215 fuRegularFrameCopyStatus = std::dynamic_pointer_cast<ZEDCamera>(m_pCamera)->RequestFrameCopy(m_cvGPUFrame);
216
217 // Wait for point cloud to be retrieved.
218 if (fuPointCloudCopyStatus.get() && fuRegularFrameCopyStatus.get())
219 {
220 // Download mat from GPU memory.
221 m_cvGPUPointCloud.download(m_cvPointCloud);
222 m_cvGPUFrame.download(m_cvFrame);
223 // Drop alpha channel.
224 cv::cvtColor(m_cvFrame, m_cvFrame, cv::COLOR_BGRA2BGR);
225 }
226 else
227 {
228 // Submit logger message.
229 LOG_WARNING(logging::g_qSharedLogger, "ObjectDetector unable to get point cloud from ZEDCam!");
230 }
231 }
232 else
233 {
234 // Grabs point cloud from ZEDCam.
235 fuPointCloudCopyStatus = std::dynamic_pointer_cast<ZEDCamera>(m_pCamera)->RequestPointCloudCopy(m_cvPointCloud);
236 fuRegularFrameCopyStatus = std::dynamic_pointer_cast<ZEDCamera>(m_pCamera)->RequestFrameCopy(m_cvFrame);
237
238 // Wait for point cloud to be retrieved.
239 if (!fuPointCloudCopyStatus.get())
240 {
241 // Submit logger message.
242 LOG_WARNING(logging::g_qSharedLogger, "ObjectDetector unable to get point cloud from ZEDCam!");
243 }
244 if (!fuRegularFrameCopyStatus.get())
245 {
246 // Submit logger message.
247 LOG_WARNING(logging::g_qSharedLogger, "ObjectDetector unable to get regular frame from ZEDCam!");
248 }
249 }
250 }
251 else
252 {
253 // Grab frames from camera.
254 fuRegularFrameCopyStatus = std::dynamic_pointer_cast<BasicCamera>(m_pCamera)->RequestFrameCopy(m_cvFrame);
255
256 // Wait for point cloud to be retrieved.
257 if (!fuRegularFrameCopyStatus.get())
258 {
259 // Submit logger message.
260 LOG_WARNING(logging::g_qSharedLogger, "ObjectDetector unable to get RGB image from BasicCam!");
261 }
262 }
263
265 // Actual detection logic goes here.
267 // Check if the frame is empty.
268 if (m_cvFrame.empty())
269 {
270 // Submit logger message.
271 LOG_WARNING(logging::g_qSharedLogger, "Frame from camera is empty!");
272 return;
273 }
274
275 // Clear the list of newly detected objects.
276 m_vNewlyDetectedObjects.clear();
277 // Clone frames.
278 m_cvTorchOverlayFrame = m_cvFrame.clone();
279 m_cvTorchProcFrame = m_cvFrame.clone();
280 // Copy the camera frame to the pre-processing frame and overlay frame.
281 cv::cvtColor(m_cvTorchProcFrame, m_cvTorchProcFrame, cv::COLOR_BGR2RGB);
282
283 // Check if torch detection if turned on.
284 if (m_bTorchEnabled)
285 {
286 // Detect objects in the image.
287 std::vector<objectdetectutils::Object> vNewTorchObjects =
288 torchobject::Detect(m_cvTorchProcFrame, *m_pTorchDetector, m_fTorchMinObjectConfidence, m_fTorchNMSThreshold);
289 // Add Torch objects to the list of newly detected objects.
290 m_vNewlyDetectedObjects.insert(m_vNewlyDetectedObjects.end(), vNewTorchObjects.begin(), vNewTorchObjects.end());
291 }
292
293 // Set the FOV of the camera in the object structs for this detector's camera.
294 for (objectdetectutils::Object& stObject : m_vNewlyDetectedObjects)
295 {
296 // Set object FOV parameter to this object detectors camera's FOV.
297 stObject.dHorizontalFOV = m_pCamera->GetPropHorizontalFOV();
298 }
299
300 // Merge the newly detected objects with the pre-existing detected objects.
301 this->UpdateDetectedObjects(m_vNewlyDetectedObjects);
302
303 // Draw object overlays onto normal image.
304 torchobject::DrawDetections(m_cvTorchOverlayFrame, m_vDetectedObjects);
306 }
307
308 // Acquire a shared_lock on the detected objects copy queue.
309 std::shared_lock<std::shared_mutex> lkSchedulers(m_muPoolScheduleMutex);
310 // Check if the detected object copy queue is empty.
311 if (!m_qDetectedObjectDrawnOverlayFramesCopySchedule.empty() || !m_qDetectedObjectCopySchedule.empty())
312 {
313 size_t siQueueLength = m_qDetectedObjectDrawnOverlayFramesCopySchedule.size() + m_qDetectedObjectCopySchedule.size();
314 // Start the thread pool to store multiple copies of the detected objects to the requesting threads
315 this->RunDetachedPool(siQueueLength, m_nNumDetectedObjectsRetrievalThreads);
316 // Wait for thread pool to finish.
317 this->JoinPool();
318 // Release lock on frame copy queue.
319 lkSchedulers.unlock();
320 }
321}
void RunDetachedPool(const unsigned int nNumTasksToQueue, const unsigned int nNumThreads=2, const bool bForceStopCurrentThreads=false)
When this method is called, it starts a thread pool full of threads that don't return std::futures (l...
Definition AutonomyThread.hpp:336
void JoinPool()
Waits for pool to finish executing tasks. This method will block the calling code until thread is fin...
Definition AutonomyThread.hpp:439
void UpdateDetectedObjects(std::vector< objectdetectutils::Object > &vNewlyDetectedObjects)
Update the detected objects with the newly detected objects.
Definition ObjectDetector.cpp:657
CV_NODISCARD_STD Mat clone() const
bool empty() const
void download(OutputArray dst) const
void cvtColor(InputArray src, OutputArray dst, int code, int dstCn=0)
COLOR_BGRA2BGR
COLOR_BGR2RGB
void DrawDetections(cv::Mat &cvDetectionsFrame, const std::vector< objectdetectutils::Object > &vDetectedTags)
Given a vector of objectdetectutils::Object structs draw each tag corner and confidence onto the give...
Definition TorchObjectDetection.hpp:102
std::vector< objectdetectutils::Object > Detect(const cv::Mat &cvFrame, yolomodel::pytorch::PyTorchInterpreter &trPyTorchDetector, const float fMinObjectConfidence=0.40f, const float fNMSThreshold=0.60f)
Detects objects in the given image using a PyTorch model.
Definition TorchObjectDetection.hpp:45
Represents a single detected object. Combines attributes from TorchObject and TensorflowObject struct...
Definition ObjectDetectionUtility.hpp:73
Here is the call graph for this function:

◆ PooledLinearCode()

void ObjectDetector::PooledLinearCode ( )
overrideprivatevirtual

This method will run in a thread pool. It will be called by the main thread and will run the code within the PooledLinearCode() method. This is meant to be used as an internal utility of the child class to further improve parallelization.

Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2025-05-05

Implements AutonomyThread< void >.

333{
335 // Detection Overlay Frame queue.
337 // Acquire sole writing access to the detectedObjectCopySchedule.
338 std::unique_lock<std::shared_mutex> lkObjectOverlayFrameQueue(m_muFrameCopyMutex);
339 // Check if there are unfulfilled requests.
340 if (!m_qDetectedObjectDrawnOverlayFramesCopySchedule.empty())
341 {
342 // Get frame container out of queue.
343 containers::FrameFetchContainer<cv::Mat> stContainer = m_qDetectedObjectDrawnOverlayFramesCopySchedule.front();
344 // Pop out of queue.
345 m_qDetectedObjectDrawnOverlayFramesCopySchedule.pop();
346 // Release lock.
347 lkObjectOverlayFrameQueue.unlock();
348
349 // Check which frame we should copy.
350 switch (stContainer.eFrameType)
351 {
352 case PIXEL_FORMATS::eObjectDetection: *stContainer.pFrame = m_cvTorchOverlayFrame.clone(); break;
353 default: *stContainer.pFrame = m_cvTorchOverlayFrame.clone(); break;
354 }
355
356 // Signal future that the frame has been successfully retrieved.
357 stContainer.pCopiedFrameStatus->set_value(true);
358 }
359
361 // Object queue.
363 // Acquire sole writing access to the detectedObjectCopySchedule.
364 std::unique_lock<std::shared_mutex> lkObjectQueue(m_muArucoDataCopyMutex);
365 // Check if there are unfulfilled requests.
366 if (!m_qDetectedObjectCopySchedule.empty())
367 {
368 // Get frame container out of queue.
369 containers::DataFetchContainer<std::vector<objectdetectutils::Object>> stContainer = m_qDetectedObjectCopySchedule.front();
370 // Pop out of queue.
371 m_qDetectedObjectCopySchedule.pop();
372 // Release lock.
373 lkObjectQueue.unlock();
374
375 // Copy the detected objects to the target location
376 *stContainer.pData = m_vDetectedObjects;
377
378 // Signal future that the frame has been successfully retrieved.
379 stContainer.pCopiedDataStatus->set_value(true);
380 }
381}
Here is the call graph for this function:

◆ UpdateDetectedObjects()

void ObjectDetector::UpdateDetectedObjects ( std::vector< objectdetectutils::Object > &  vNewlyDetectedObjects)
private

Update the detected objects with the newly detected objects.

Parameters
vNewlyDetectedObjects- The vector of newly detected objects to update the detected objects with.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2025-05-05
658{
659 // Check if tracking is enabled.
660 if (m_bEnableTracking)
661 {
662 // Check if the given object vector is empty
663 if (vNewlyDetectedObjects.empty())
664 {
665 // Since the objects are empty that means the detector has not detected any new ground truth objects.
666 // In this case we will fallback to relying on the multi-tracker to track the objects and just update the objects
667 // stored in the m_vDetectedObjects vector.
668 // This is necessary because the torch detector is not perfect and may not detect all objects in the frame
669 // and it doesn't have the ability to track objects over time.
670 // We will use the multi-tracker to track the objects over time and update the bounding box data for the objects.
671
672 // Update the multi-tracker with the current frame.
673 m_pMultiTracker->Update(m_cvFrame);
674 }
675 else
676 {
677 // Loop through the newly detected objects.
678 for (objectdetectutils::Object& stObject : vNewlyDetectedObjects)
679 {
680 // Add the newly detected objects to the multi-tracker.
681 bool bMatchedObjectToExistingTracker = m_pMultiTracker->InitTracker(m_cvFrame, stObject.pBoundingBox, constants::BBOX_TRACKER_TYPE);
682 // Check if the object was matched to an existing tracker.
683 if (!bMatchedObjectToExistingTracker)
684 {
685 // Add the new object to the member variable list.
686 m_vDetectedObjects.emplace_back(stObject);
687 }
688 else
689 {
690 // Find the object with the same bounding box pointer and update the ID and confidence.
691 for (objectdetectutils::Object& stExistingObject : m_vDetectedObjects)
692 {
693 // Check if the bounding box pointers are the same.
694 if (stObject.pBoundingBox == stExistingObject.pBoundingBox)
695 {
696 // Update the ID and confidence of the existing object.
697 stExistingObject.dConfidence = stObject.dConfidence;
698 }
699 }
700 }
701 }
702
703 // Update the multi-tracker with the current frame.
704 m_pMultiTracker->Update(m_cvFrame);
705 }
706
707 // Loop through the detected objects and check if there are any we need to remove, and also update the time last seen.
708 for (std::vector<objectdetectutils::Object>::iterator itObject = m_vDetectedObjects.begin(); itObject != m_vDetectedObjects.end();)
709 {
710 // Check if the bounding box is 0,0,0,0.
711 if (itObject->pBoundingBox->x == 0 && itObject->pBoundingBox->y == 0 && itObject->pBoundingBox->width == 0 && itObject->pBoundingBox->height == 0)
712 {
713 // Remove the object from the vector.
714 itObject = m_vDetectedObjects.erase(itObject);
715 }
716 else
717 {
718 ++itObject;
719 }
720 }
721 }
722 else
723 {
724 // If tracking is not enabled, we will just clear the detected objects and add the new ones.
725 m_vDetectedObjects.clear();
726 // Loop through the newly detected objects and add them to the detected objects vector.
727 for (objectdetectutils::Object& stObject : vNewlyDetectedObjects)
728 {
729 // Set the object creation time to 0. The objects aren't being tracked, so we can't really tell their age.
730 stObject.tmCreation = std::chrono::system_clock::time_point::min();
731
732 // Add the new object to the member variable list.
733 m_vDetectedObjects.emplace_back(stObject);
734 }
735 }
736
737 // Check if we are using a ZED camera.
738 if (m_bUsingZedCamera)
739 {
740 // Check if the point cloud is empty.
741 if (!m_cvPointCloud.empty())
742 {
743 // Get the rover pose from the waypoint handler.
744 m_stRoverPose = globals::g_pWaypointHandler->SmartRetrieveRoverPose();
745 // Loop through the objects and use their center point to lookup their distance in the point cloud.
746 for (objectdetectutils::Object& stObject : m_vDetectedObjects)
747 {
748 // Use either width of height for the neighborhood size.
749 int nNeighborhoodSize = std::min(stObject.pBoundingBox->width, stObject.pBoundingBox->height);
750 // Geolocate the object in the point cloud.
751 stObject.stGeolocatedPosition =
752 geoloc::GeolocateBox(m_cvPointCloud, m_stRoverPose, cv::Point(stObject.pBoundingBox->x, stObject.pBoundingBox->y), nNeighborhoodSize);
753
754 // Since this is a object detection, set the object's waypoint type appropriately.
755 stObject.stGeolocatedPosition.eType = geoops::WaypointType::eObjectWaypoint;
756 // Depending on the class name of the model, set the object type.
757 if (stObject.szClassName == "mallet")
758 {
759 stObject.eDetectionType = objectdetectutils::ObjectDetectionType::eMallet;
760 }
761 else if (stObject.szClassName == "bottles")
762 {
763 stObject.eDetectionType = objectdetectutils::ObjectDetectionType::eWaterBottle;
764 }
765
766 // Calculate the geo measurement and print the distance to the object.
767 geoops::GeoMeasurement stMeasurement =
768 geoops::CalculateGeoMeasurement(m_stRoverPose.GetUTMCoordinate(), stObject.stGeolocatedPosition.GetUTMCoordinate());
769 // Set the straight line distance to the object.
770 stObject.dStraightLineDistance = stMeasurement.dDistanceMeters;
771 // Use the rover heading and the azimuth angle to calculate the relative heading to the object.
772 stObject.dYawAngle = numops::AngularDifference(m_stRoverPose.GetCompassHeading(), stMeasurement.dStartRelativeBearing);
773 }
774 }
775 }
776 else
777 {
778 // Estimate the positions of the objects using some basic trig.
779 for (objectdetectutils::Object& stObject : m_vDetectedObjects)
780 {
781 // Use some trig to get the location of the object.
783 }
784 }
785}
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
geoops::Waypoint GeolocateBox(const cv::Mat &cvPointcloud, const geoops::RoverPose &stRoverPose, const cv::Point &cvPixel, int nNeighborhoodSize=5)
Converts pixel coordinates in a ZED2i pointcloud into global UTM coordinates, given the rover's curre...
Definition Geolocate.hpp:55
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
constexpr T AngularDifference(T tFirstValue, T tSecondValue)
Calculates the distance in degrees between two angles. This function accounts for wrap around so that...
Definition NumberOperations.hpp:204
void EstimatePoseFromCameraFrame(Object &stTag)
Estimate the pose of a tag from a camera frame.
Definition ObjectDetectionUtility.hpp:176
This struct is used to store the distance, arc length, and relative bearing for a calculated geodesic...
Definition GeospatialOperations.hpp:82
double GetCompassHeading() const
Accessor for the Compass Heading private member.
Definition GeospatialOperations.hpp:756
const geoops::UTMCoordinate & GetUTMCoordinate() const
Accessor for the geoops::UTMCoordinate member variable.
Definition GeospatialOperations.hpp:736
Here is the call graph for this function:
Here is the caller graph for this function:

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