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

This class implements and interfaces with the SIM cameras and data. It is designed in such a way that multiple other classes/threads can safely call any method of an object of this class withing resource corruption or slowdown of the camera. More...

#include <SIMZEDCam.h>

Inheritance diagram for SIMZEDCam:
Collaboration diagram for SIMZEDCam:

Public Member Functions

 SIMZEDCam (const std::string szCameraPath, const int nPropResolutionX, const int nPropResolutionY, const int nPropFramesPerSecond, const double dPropHorizontalFOV, const double dPropVerticalFOV, const bool bEnableRecordingFlag, const int nNumFrameRetrievalThreads=10, const unsigned int unCameraSerialNumber=0)
 Construct a new SIM Cam:: SIM Cam object.
 
 ~SIMZEDCam ()
 Destroy the SIM Cam:: SIM Cam object.
 
std::future< bool > RequestFrameCopy (cv::Mat &cvFrame) override
 Puts a frame pointer into a queue so a copy of a frame from the camera can be written to it. Remember, this code will be ran in whatever, class/thread calls it.
 
std::future< bool > RequestDepthCopy (cv::Mat &cvDepth, const bool bRetrieveMeasure=true)
 Requests a depth measure or image from the camera. Puts a frame pointer into a queue so a copy of a frame from the camera can be written to it. This image has the same shape as a grayscale image, but the values represent the depth in MILLIMETERS. The ZEDSDK will always return this measure in MILLIMETERS.
 
std::future< bool > RequestPointCloudCopy (cv::Mat &cvPointCloud)
 Requests a point cloud image from the camera. This image has the same resolution as a normal image but with three XYZ values replacing the old color values in the 3rd dimension. The units and sign of the XYZ values are determined by ZED_MEASURE_UNITS and ZED_COORD_SYSTEM constants set in AutonomyConstants.h.
 
std::future< bool > RequestPositionalPoseCopy (Pose &stPose) override
 Puts a sl::GeoPose pointer into a queue so a copy of a GeoPose from the camera can be written to it.
 
std::future< bool > RequestFusionGeoPoseCopy (sl::GeoPose &slGeoPose) override
 Puts a sl::GeoPose pointer into a queue so a copy of a GeoPose from the camera can be written to it.
 
std::future< bool > RequestSensorsCopy (sl::SensorsData &slSensorsData) override
 Requests a copy of the sensors data from the camera.
 
sl::ERROR_CODE ResetPositionalTracking () override
 This method is used to reset the positional tracking of the camera. Because this is a simulation camera, and then ZEDSDK is not available, this method will just reset the offsets to zero.
 
sl::ERROR_CODE RebootCamera () override
 This method is used to reboot the camera. This method will stop the camera thread, join the camera thread, destroy the camera stream objects, reconstruct the camera stream objects, set the frame callbacks, and restart the camera thread. This simulates a camera reboot since the ZED SDK is not available.
 
sl::FUSION_ERROR_CODE SubscribeFusionToCameraUUID (sl::CameraIdentifier &slCameraUUID) override
 This method is used to subscribe the sl::Fusion object to the camera with the given UUID. Given that this is a simulation camera, and the ZED SDK is not available, this method will do nothing.
 
sl::CameraIdentifier PublishCameraToFusion () override
 This method is used to publish the camera to the sl::Fusion object. Since this is a simulation camera this will do nothing.
 
sl::ERROR_CODE EnablePositionalTracking (const float fExpectedCameraHeightFromFloorTolerance=constants::ZED_DEFAULT_FLOOR_PLANE_ERROR) override
 This method is used to enable positional tracking on the camera. Since this is a simulation camera, this method will just set the member variable and then use the NavBoard to simulate the camera's position.
 
void DisablePositionalTracking () override
 This method is used to disable positional tracking on the camera. Since this is a simulation camera, this method will just set the member variable.
 
void SetPositionalPose (const double dX, const double dY, const double dZ, const double dXO, const double dYO, const double dZO) override
 This method is used to set the positional pose of the camera. Since this is a simulation camera, this method will just set the offset member variables.
 
bool GetCameraIsOpen () override
 Accessor for the camera open status.
 
bool GetUsingGPUMem () const override
 Returns if the camera is using GPU memory. This is a simulation camera, so this method will always return false.
 
std::string GetCameraModel () override
 Accessor for the name of this model of camera.
 
bool GetPositionalTrackingEnabled () override
 Accessor for the if the camera's positional tracking is enabled. Since this is a simulation camera, this method will just return the member variable.
 
- Public Member Functions inherited from ZEDCamera
 ZEDCamera (const int nPropResolutionX, const int nPropResolutionY, const int nPropFramesPerSecond, const double dPropHorizontalFOV, const double dPropVerticalFOV, const bool bEnableRecordingFlag, const bool bMemTypeGPU, const bool bUseHalfDepthPrecision, const bool bEnableFusionMaster, const int nNumFrameRetrievalThreads, const unsigned int unCameraSerialNumber)
 Construct a new ZEDCamera object.
 
virtual ~ZEDCamera ()=default
 Destroy the ZEDCamera object.
 
virtual std::future< bool > RequestFrameCopy (cv::cuda::GpuMat &cvGPUFrame)
 Puts a frame pointer into a queue so a copy of a frame from the camera can be written to it.
 
virtual std::future< bool > RequestDepthCopy (cv::cuda::GpuMat &cvGPUDepth, const bool bRetrieveMeasure=true)
 Puts a frame pointer into a queue so a copy of a depth frame from the camera can be written to it.
 
virtual std::future< bool > RequestPointCloudCopy (cv::cuda::GpuMat &cvGPUPointCloud)
 Puts a frame pointer into a queue so a copy of a point cloud from the camera can be written to it.
 
virtual std::future< bool > RequestFloorPlaneCopy (sl::Plane &slFloorPlane)
 Puts a FloorPlane pointer into a queue so a copy of a FloorPlane from the camera can be written to it.
 
virtual std::future< bool > RequestObjectsCopy (std::vector< sl::ObjectData > &vObjectData)
 Puts a vector of ObjectData pointers into a queue so a copy of a vector of ObjectData from the camera can be written to it.
 
virtual std::future< bool > RequestBatchedObjectsCopy (std::vector< sl::ObjectsBatch > &vBatchedObjectData)
 Puts a vector of ObjectsBatch pointers into a queue so a copy of a vector of ObjectsBatch from the camera can be written to it.
 
virtual sl::ERROR_CODE TrackCustomBoxObjects (std::vector< ZedObjectData > &vCustomObjects)
 Tracks custom bounding boxes in the camera's field of view.
 
virtual sl::FUSION_ERROR_CODE IngestGPSDataToFusion (geoops::GPSCoordinate stNewGPSLocation)
 Ingests GPS data into the fusion object.
 
virtual sl::ERROR_CODE EnableSpatialMapping ()
 Enables spatial mapping.
 
virtual void DisableSpatialMapping ()
 Disables spatial mapping.
 
virtual sl::ERROR_CODE EnableObjectDetection (const bool bEnableBatching=false)
 Enables object detection.
 
virtual void DisableObjectDetection ()
 Disables object detection.
 
virtual bool GetIsFusionMaster () const
 Accessor for if this ZED is running a fusion instance.
 
virtual unsigned int GetCameraSerial ()
 Accessor for the Camera Serial private member.
 
virtual sl::PositionalTrackingStatus GetPositionalTrackingState ()
 Accessor for the Positional Tracking State private member.
 
virtual sl::FusedPositionalTrackingStatus GetFusedPositionalTrackingState ()
 Accessor for the Fused Positional Tracking State private member.
 
virtual sl::SPATIAL_MAPPING_STATE GetSpatialMappingState ()
 Accessor for the Spatial Mapping State private member.
 
virtual sl::SPATIAL_MAPPING_STATE ExtractSpatialMapAsync (std::future< sl::Mesh > &fuMeshFuture)
 Puts a Mesh pointer into a queue so a copy of a spatial mapping mesh from the camera can be written to it.
 
virtual bool GetObjectDetectionEnabled ()
 Accessor for the Object Detection Enabled private member.
 
- Public Member Functions inherited from Camera< cv::Mat >
 Camera (const int nPropResolutionX, const int nPropResolutionY, const int nPropFramesPerSecond, const PIXEL_FORMATS ePropPixelFormat, const double dPropHorizontalFOV, const double dPropVerticalFOV, const bool bEnableRecordingFlag, const int nNumFrameRetrievalThreads=5)
 Construct a new Camera object.
 
virtual ~Camera ()
 Destroy the Camera object.
 
cv::Size GetPropResolution () const
 Accessor for the Prop Resolution private member.
 
int GetPropFramesPerSecond () const
 Accessor for the Prop Frames Per Second private member.
 
PIXEL_FORMATS GetPropPixelFormat () const
 Accessor for the Prop Pixel Format private member.
 
double GetPropHorizontalFOV () const
 Accessor for the Prop Horizontal F O V private member.
 
double GetPropVerticalFOV () const
 Accessor for the Prop Vertical F O V private member.
 
bool GetEnableRecordingFlag () const
 Accessor for the Enable Recording Flag private member.
 
void SetEnableRecordingFlag (const bool bEnableRecordingFlag)
 Mutator for the Enable Recording Flag private member.
 
- 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
 The code inside this private method runs in a separate thread, but still has access to this*. This method continuously get new frames from the OpenCV VideoCapture object and stores it in a member variable. Then a thread pool is started and joined once per iteration to mass copy the frames and/or measure to any other thread waiting in the queues.
 
void PooledLinearCode () override
 This method holds the code that is ran in the thread pool started by the ThreadedLinearCode() method. It copies the data from the different data objects to references of the same type stored in a vector queued up by the Grab methods.
 
void SetCallbacks ()
 This method sets the callbacks for the WebRTC connections.
 
void EstimateDepthMeasure (const cv::Mat &cvDepthImage, cv::Mat &cvDepthMeasure)
 This method estimates the depth measure from the depth image.
 
void CalculatePointCloud (const cv::Mat &cvDepthMeasure, cv::Mat &cvPointCloud)
 This method calculates a point cloud from the decoded depth measure use some simple trig and the camera FOV.
 

Private Attributes

const std::function< void(const rovecomm::RoveCommPacket< double > &, const sockaddr_in &)> ProcessIMUData
 Callback function to process incoming IMU data from RoveComm for the SIM ZED Camera. Normally, this data would come from the physical ZED camera's IMU over USB,.
 
std::string m_szCameraPath
 
std::atomic< bool > m_bCameraPositionalTrackingEnabled
 
sl::SensorsData m_stIMUData
 
std::unique_ptr< WebRTCm_pRGBStream
 
std::unique_ptr< WebRTCm_pDepthImageStream
 
double m_dPoseOffsetX
 
double m_dPoseOffsetY
 
double m_dPoseOffsetZ
 
double m_dPoseOffsetXO
 
double m_dPoseOffsetYO
 
double m_dPoseOffsetZO
 
geoops::RoverPose m_stCurrentRoverPose
 
std::shared_mutex m_muCurrentRoverPoseMutex
 
cv::Mat m_cvFrame
 
cv::Mat m_cvDepthImageBuffer
 
cv::Mat m_cvDepthImage
 
cv::Mat m_cvDepthMeasure
 
cv::Mat m_cvPointCloud
 
std::queue< containers::DataFetchContainer< Pose > > m_qPoseCopySchedule
 
std::queue< containers::DataFetchContainer< sl::GeoPose > > m_qGeoPoseCopySchedule
 
std::queue< containers::DataFetchContainer< sl::SensorsData > > m_qSensorsCopySchedule
 
std::shared_mutex m_muWebRTCRGBImageCopyMutex
 
std::shared_mutex m_muWebRTCDepthImageCopyMutex
 
std::shared_mutex m_muPoseCopyMutex
 
std::shared_mutex m_muGeoPoseCopyMutex
 
std::shared_mutex m_muSensorsCopyMutex
 
std::atomic< bool > m_bPosesQueued
 
std::atomic< bool > m_bGeoPosesQueued
 
std::atomic< bool > m_bSensorsQueued
 

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 ZEDCamera
const std::memory_order ATOMIC_MEMORY_ORDER_METHOD = std::memory_order_relaxed
 
unsigned int m_unCameraSerialNumber
 
bool m_bCameraIsFusionMaster
 
- Protected Attributes inherited from Camera< cv::Mat >
int m_nPropResolutionX
 
int m_nPropResolutionY
 
int m_nPropFramesPerSecond
 
int m_nNumFrameRetrievalThreads
 
PIXEL_FORMATS m_ePropPixelFormat
 
double m_dPropHorizontalFOV
 
double m_dPropVerticalFOV
 
std::atomic_bool m_bEnableRecordingFlag
 
std::queue< containers::FrameFetchContainer< cv::Mat > > m_qFrameCopySchedule
 
std::shared_mutex m_muPoolScheduleMutex
 
std::shared_mutex m_muFrameCopyMutex
 
- Protected Attributes inherited from AutonomyThread< void >
IPS m_IPS
 

Detailed Description

This class implements and interfaces with the SIM cameras and data. It is designed in such a way that multiple other classes/threads can safely call any method of an object of this class withing resource corruption or slowdown of the camera.

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

Constructor & Destructor Documentation

◆ SIMZEDCam()

SIMZEDCam::SIMZEDCam ( const std::string  szCameraPath,
const int  nPropResolutionX,
const int  nPropResolutionY,
const int  nPropFramesPerSecond,
const double  dPropHorizontalFOV,
const double  dPropVerticalFOV,
const bool  bEnableRecordingFlag,
const int  nNumFrameRetrievalThreads = 10,
const unsigned int  unCameraSerialNumber = 0 
)

Construct a new SIM Cam:: SIM Cam object.

Parameters
szCameraPath- The file path to the camera hardware.
nPropResolutionX- X res of camera.
nPropResolutionY- Y res of camera.
nPropFramesPerSecond- FPS camera is running at.
ePropPixelFormat- The pixel layout/format of the image.
dPropHorizontalFOV- The horizontal field of view.
dPropVerticalFOV- The vertical field of view.
bEnableRecordingFlag- Whether or not this camera should be recorded.
nNumFrameRetrievalThreads- The number of threads to use for frame queueing and copying.
unCameraSerialNumber- The serial number of the camera.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-09-30
51 :
52 ZEDCamera(nPropResolutionX,
53 nPropResolutionY,
54 nPropFramesPerSecond,
55 dPropHorizontalFOV,
56 dPropVerticalFOV,
57 bEnableRecordingFlag,
58 false,
59 false,
60 false,
61 nNumFrameRetrievalThreads,
62 unCameraSerialNumber)
63{
64 // Assign member variables.
65 m_szCameraPath = szCameraPath;
66 m_nNumFrameRetrievalThreads = nNumFrameRetrievalThreads;
67
68 // Initialize OpenCV mats to a black/empty image the size of the camera resolution.
69 m_cvFrame = cv::Mat::zeros(nPropResolutionY, nPropResolutionX, CV_8UC4);
70 m_cvDepthImage = cv::Mat::zeros(nPropResolutionY, nPropResolutionX, CV_8UC1);
71 m_cvDepthMeasure = cv::Mat::zeros(nPropResolutionY, nPropResolutionX, CV_32FC1);
72 m_cvPointCloud = cv::Mat::zeros(nPropResolutionY, nPropResolutionX, CV_32FC4);
73
74 // Construct camera stream objects. Append proper camera path arguments to each URL camera path.
75 m_pRGBStream = std::make_unique<WebRTC>(szCameraPath, "ZEDFrontRGB");
76 m_pDepthImageStream = std::make_unique<WebRTC>(szCameraPath, "ZEDFrontDepthImage");
77
78 // Set callbacks for the WebRTC connections.
79 this->SetCallbacks();
80
81 // Subscribe to RoveSoSimulator packets.
82 rovecomm::RoveCommPacket<u_int8_t> stSubscribePacket;
83 stSubscribePacket.unDataId = manifest::System::SUBSCRIBE_DATA_ID;
84 stSubscribePacket.unDataCount = 0;
85 stSubscribePacket.eDataType = manifest::DataTypes::UINT8_T;
86 stSubscribePacket.vData = std::vector<uint8_t>{};
87 // Set RoveComm callbacks for the data from the sim.
88 if (network::g_pRoveCommUDPNode)
89 {
90 // Determine the IP address to send the subscribe packet to.
91 const char* cIPAddress = constants::MODE_SIM ? constants::SIM_IP_ADDRESS.c_str() : manifest::RoveSoSimulator::IP_ADDRESS.IP_STR.c_str();
92
93 // Send subscribe packet to RoveSoSimulator.
94 network::g_pRoveCommUDPNode->SendUDPPacket(stSubscribePacket, cIPAddress, constants::ROVECOMM_OUTGOING_UDP_PORT);
95
96 // Set RoveComm callbacks.
97 network::g_pRoveCommUDPNode->AddUDPCallback<double>(ProcessIMUData, manifest::RoveSoSimulator::TELEMETRY.find("IMU")->second.DATA_ID);
98 }
99
100 // Set max FPS of the ThreadedContinuousCode method.
101 this->SetMainThreadIPSLimit(nPropFramesPerSecond);
102}
void SetMainThreadIPSLimit(int nMaxIterationsPerSecond=0)
Mutator for the Main Thread Max I P S private member.
Definition AutonomyThread.hpp:467
void SetCallbacks()
This method sets the callbacks for the WebRTC connections.
Definition SIMZEDCam.cpp:135
const std::function< void(const rovecomm::RoveCommPacket< double > &, const sockaddr_in &)> ProcessIMUData
Callback function to process incoming IMU data from RoveComm for the SIM ZED Camera....
Definition SIMZEDCam.h:99
This class serves as a middle inheritor between the Camera interface and the ZEDCam class....
Definition ZEDCamera.hpp:33
static CV_NODISCARD_STD MatExpr zeros(int rows, int cols, int type)
Here is the call graph for this function:

◆ ~SIMZEDCam()

SIMZEDCam::~SIMZEDCam ( )

Destroy the SIM Cam:: SIM Cam object.

Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-09-30
112{
113 // Close the WebRTC connections.
114 if (m_pRGBStream)
115 {
116 m_pRGBStream->CloseConnection();
117 }
118 if (m_pDepthImageStream)
119 {
120 m_pDepthImageStream->CloseConnection();
121 }
122
123 // Stop threaded code.
124 this->RequestStop();
125 this->Join();
126}
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
Here is the call graph for this function:

Member Function Documentation

◆ RequestFrameCopy()

std::future< bool > SIMZEDCam::RequestFrameCopy ( cv::Mat cvFrame)
overridevirtual

Puts a frame pointer into a queue so a copy of a frame from the camera can be written to it. Remember, this code will be ran in whatever, class/thread calls it.

Parameters
cvFrame- A reference to the cv::Mat to store the frame in.
Returns
std::future<bool> - A future that should be waited on before the passed in frame is used. Value will be true if frame was successfully retrieved.
Author
ClayJay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-09-30

Implements ZEDCamera.

534{
535 // Assemble the FrameFetchContainer.
536 containers::FrameFetchContainer<cv::Mat> stContainer(cvFrame, m_ePropPixelFormat);
537
538 // Acquire lock on frame copy queue.
539 std::unique_lock<std::shared_mutex> lkScheduler(m_muPoolScheduleMutex);
540 // Append frame fetch container to the schedule queue.
541 m_qFrameCopySchedule.push(stContainer);
542 // Release lock on the frame schedule queue.
543 lkScheduler.unlock();
544
545 // Return the future from the promise stored in the container.
546 return stContainer.pCopiedFrameStatus->get_future();
547}
This struct is used to carry references to camera frames for scheduling and copying....
Definition FetchContainers.hpp:89

◆ RequestDepthCopy()

std::future< bool > SIMZEDCam::RequestDepthCopy ( cv::Mat cvDepth,
const bool  bRetrieveMeasure = true 
)
virtual

Requests a depth measure or image from the camera. Puts a frame pointer into a queue so a copy of a frame from the camera can be written to it. This image has the same shape as a grayscale image, but the values represent the depth in MILLIMETERS. The ZEDSDK will always return this measure in MILLIMETERS.

Parameters
cvDepth- A reference to the cv::Mat to copy the depth frame to.
bRetrieveMeasure- False to get depth IMAGE instead of MEASURE. Do not use the 8-bit grayscale depth image purposes other than displaying depth.
Returns
std::future<bool> - A future that should be waited on before the passed in frame is used. Value will be true if frame was successfully retrieved.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-08-26

Implements ZEDCamera.

565{
566 // Create instance variables.
567 PIXEL_FORMATS eFrameType;
568
569 // Check if the container should be set to retrieve an image or a measure.
570 bRetrieveMeasure ? eFrameType = PIXEL_FORMATS::eDepthMeasure : eFrameType = PIXEL_FORMATS::eDepthImage;
571 // Assemble container.
572 containers::FrameFetchContainer<cv::Mat> stContainer(cvDepth, eFrameType);
573
574 // Acquire lock on frame copy queue.
575 std::unique_lock<std::shared_mutex> lkSchedulers(m_muPoolScheduleMutex);
576 // Append frame fetch container to the schedule queue.
577 m_qFrameCopySchedule.push(stContainer);
578 // Release lock on the frame schedule queue.
579 lkSchedulers.unlock();
580
581 // Return the future from the promise stored in the container.
582 return stContainer.pCopiedFrameStatus->get_future();
583}

◆ RequestPointCloudCopy()

std::future< bool > SIMZEDCam::RequestPointCloudCopy ( cv::Mat cvPointCloud)
virtual

Requests a point cloud image from the camera. This image has the same resolution as a normal image but with three XYZ values replacing the old color values in the 3rd dimension. The units and sign of the XYZ values are determined by ZED_MEASURE_UNITS and ZED_COORD_SYSTEM constants set in AutonomyConstants.h.

Puts a frame pointer into a queue so a copy of a frame from the camera can be written to it.

Parameters
cvPointCloud- A reference to the cv::Mat to copy the point cloud frame to.
Returns
std::future<bool> - A future that should be waited on before the passed in frame is used. Value will be true if frame was successfully retrieved.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-08-26

Implements ZEDCamera.

601{
602 // Assemble the FrameFetchContainer.
603 containers::FrameFetchContainer<cv::Mat> stContainer(cvPointCloud, PIXEL_FORMATS::eXYZ);
604
605 // Acquire lock on frame copy queue.
606 std::unique_lock<std::shared_mutex> lkSchedulers(m_muPoolScheduleMutex);
607 // Append frame fetch container to the schedule queue.
608 m_qFrameCopySchedule.push(stContainer);
609 // Release lock on the frame schedule queue.
610 lkSchedulers.unlock();
611
612 // Return the future from the promise stored in the container.
613 return stContainer.pCopiedFrameStatus->get_future();
614}

◆ RequestPositionalPoseCopy()

std::future< bool > SIMZEDCam::RequestPositionalPoseCopy ( ZEDCamera::Pose stPose)
overridevirtual

Puts a sl::GeoPose pointer into a queue so a copy of a GeoPose from the camera can be written to it.

Parameters
stPose- A reference to the sl::GeoPose to store the GeoPose in.
Returns
std::future<bool> - A future that should be waited on before the passed in GeoPose is used.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-26

Implements ZEDCamera.

626{
627 // Check if positional tracking is enabled.
628 if (m_bCameraPositionalTrackingEnabled)
629 {
630 // Assemble the data container.
631 containers::DataFetchContainer<Pose> stContainer(stPose);
632
633 // Acquire lock on pose copy queue.
634 std::unique_lock<std::shared_mutex> lkSchedulers(m_muPoolScheduleMutex);
635 // Append pose fetch container to the schedule queue.
636 m_qPoseCopySchedule.push(stContainer);
637 // Release lock on the pose schedule queue.
638 lkSchedulers.unlock();
639
640 // Check if pose queue toggle has already been set.
641 if (!m_bPosesQueued.load(ATOMIC_MEMORY_ORDER_METHOD))
642 {
643 // Signify that the pose queue is not empty.
644 m_bPosesQueued.store(true, ATOMIC_MEMORY_ORDER_METHOD);
645 }
646
647 // Return the future from the promise stored in the container.
648 return stContainer.pCopiedDataStatus->get_future();
649 }
650 else
651 {
652 // Submit logger message.
653 LOG_WARNING(logging::g_qSharedLogger, "Attempted to get ZED positional pose but positional tracking is not enabled or is still initializing!");
654
655 // Create dummy promise to return the future.
656 std::promise<bool> pmDummyPromise;
657 std::future<bool> fuDummyFuture = pmDummyPromise.get_future();
658 // Set future value.
659 pmDummyPromise.set_value(false);
660
661 // Return unsuccessful.
662 return fuDummyFuture;
663 }
664}
This struct is used to carry references to any datatype for scheduling and copying....
Definition FetchContainers.hpp:165

◆ RequestFusionGeoPoseCopy()

std::future< bool > SIMZEDCam::RequestFusionGeoPoseCopy ( sl::GeoPose &  slGeoPose)
overridevirtual

Puts a sl::GeoPose pointer into a queue so a copy of a GeoPose from the camera can be written to it.

Parameters
slGeoPose- A reference to the sl::GeoPose to store the GeoPose in.
Returns
std::future<bool> - A future that should be waited on before the passed in GeoPose is used.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-26

Implements ZEDCamera.

676{
677 // Check if positional tracking has been enabled.
678 if (m_bCameraIsFusionMaster && m_bCameraPositionalTrackingEnabled)
679 {
680 // Assemble the data container.
681 containers::DataFetchContainer<sl::GeoPose> stContainer(slGeoPose);
682
683 // Acquire lock on frame copy queue.
684 std::unique_lock<std::shared_mutex> lkSchedulers(m_muPoolScheduleMutex);
685 // Append frame fetch container to the schedule queue.
686 m_qGeoPoseCopySchedule.push(stContainer);
687 // Release lock on the frame schedule queue.
688 lkSchedulers.unlock();
689
690 // Check if pose queue toggle has already been set.
691 if (!m_bGeoPosesQueued.load(ATOMIC_MEMORY_ORDER_METHOD))
692 {
693 // Signify that the pose queue is not empty.
694 m_bGeoPosesQueued.store(true, ATOMIC_MEMORY_ORDER_METHOD);
695 }
696
697 // Return the future from the promise stored in the container.
698 return stContainer.pCopiedDataStatus->get_future();
699 }
700 else
701 {
702 // Submit logger message.
703 LOG_WARNING(logging::g_qSharedLogger,
704 "Attempted to get ZED FUSION geo pose but positional tracking is not enabled and/or this camera was not initialized as a Fusion Master!");
705
706 // Create dummy promise to return the future.
707 std::promise<bool> pmDummyPromise;
708 std::future<bool> fuDummyFuture = pmDummyPromise.get_future();
709 // Set future value.
710 pmDummyPromise.set_value(false);
711
712 // Return unsuccessful.
713 return fuDummyFuture;
714 }
715}

◆ RequestSensorsCopy()

std::future< bool > SIMZEDCam::RequestSensorsCopy ( sl::SensorsData &  slSensorsData)
overridevirtual

Requests a copy of the sensors data from the camera.

Parameters
slSensorsData- A reference to the sl::SensorsData to store the sensors data in.
Returns
std::future<bool> - A future that should be waited on before the passed in sensors data is used.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2025-08-26

Reimplemented from ZEDCamera.

727{
728 // Assemble the DataFetchContainer.
729 containers::DataFetchContainer<sl::SensorsData> stContainer(slSensorsData);
730
731 // Acquire lock on data copy queue.
732 std::unique_lock<std::shared_mutex> lkSchedulers(m_muPoolScheduleMutex);
733 // Append data fetch container to the schedule queue.
734 m_qSensorsCopySchedule.push(stContainer);
735 // Release lock on the data schedule queue.
736 lkSchedulers.unlock();
737
738 // Check if pose queue toggle has already been set.
739 if (!m_bSensorsQueued.load(ATOMIC_MEMORY_ORDER_METHOD))
740 {
741 // Signify that the pose queue is not empty.
742 m_bSensorsQueued.store(true, ATOMIC_MEMORY_ORDER_METHOD);
743 }
744
745 // Return the future from the promise stored in the container.
746 return stContainer.pCopiedDataStatus->get_future();
747}

◆ ResetPositionalTracking()

sl::ERROR_CODE SIMZEDCam::ResetPositionalTracking ( )
overridevirtual

This method is used to reset the positional tracking of the camera. Because this is a simulation camera, and then ZEDSDK is not available, this method will just reset the offsets to zero.

Returns
sl::ERROR_CODE - The error code returned by the ZED SDK. In this case, it will always be SUCCESS.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-26

Implements ZEDCamera.

760{
761 // Reset offsets back to zero.
762 m_dPoseOffsetX = 0.0;
763 m_dPoseOffsetY = 0.0;
764 m_dPoseOffsetZ = 0.0;
765 m_dPoseOffsetXO = 0.0;
766 m_dPoseOffsetYO = 0.0;
767 m_dPoseOffsetZO = 0.0;
768
769 return sl::ERROR_CODE::SUCCESS;
770}
Here is the caller graph for this function:

◆ RebootCamera()

sl::ERROR_CODE SIMZEDCam::RebootCamera ( )
overridevirtual

This method is used to reboot the camera. This method will stop the camera thread, join the camera thread, destroy the camera stream objects, reconstruct the camera stream objects, set the frame callbacks, and restart the camera thread. This simulates a camera reboot since the ZED SDK is not available.

Returns
sl::ERROR_CODE - The error code returned by the ZED SDK. In this case, it will always be SUCCESS. Even if the streams are not successfully reconnected, the camera will still be considered open.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-26

Implements ZEDCamera.

785{
786 // Stop the camera thread.
787 this->RequestStop();
788 // Join the camera thread.
789 this->Join();
790
791 // Destroy the camera stream objects.
792 m_pRGBStream.reset();
793 m_pDepthImageStream.reset();
794 // Reconstruct camera stream objects. Append proper camera path arguments to each URL camera path.
795 m_pRGBStream = std::make_unique<WebRTC>(m_szCameraPath, "ZEDFrontRGB");
796 m_pDepthImageStream = std::make_unique<WebRTC>(m_szCameraPath, "ZEDFrontDepthImage");
797
798 // Set the frame callbacks.
799 this->SetCallbacks();
800
801 // Restart the camera thread.
802 this->Start();
803
804 return sl::ERROR_CODE::SUCCESS;
805}
void Start()
When this method is called, it starts a new thread that runs the code within the ThreadedContinuousCo...
Definition AutonomyThread.hpp:117
Here is the call graph for this function:
Here is the caller graph for this function:

◆ SubscribeFusionToCameraUUID()

sl::FUSION_ERROR_CODE SIMZEDCam::SubscribeFusionToCameraUUID ( sl::CameraIdentifier &  slCameraUUID)
overridevirtual

This method is used to subscribe the sl::Fusion object to the camera with the given UUID. Given that this is a simulation camera, and the ZED SDK is not available, this method will do nothing.

Parameters
slCameraUUID- The UUID of the camera to subscribe to.
Returns
sl::FUSION_ERROR_CODE - The error code returned by the ZED SDK. In this case, it will always be SUCCESS.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-26

Implements ZEDCamera.

819{
820 // Unused parameter.
821 (void) slCameraUUID;
822
823 return sl::FUSION_ERROR_CODE::SUCCESS;
824}

◆ PublishCameraToFusion()

sl::CameraIdentifier SIMZEDCam::PublishCameraToFusion ( )
overridevirtual

This method is used to publish the camera to the sl::Fusion object. Since this is a simulation camera this will do nothing.

Returns
sl::CameraIdentifier - The identifier of the camera.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-26

Implements ZEDCamera.

836{
837 return sl::CameraIdentifier(m_unCameraSerialNumber);
838}

◆ EnablePositionalTracking()

sl::ERROR_CODE SIMZEDCam::EnablePositionalTracking ( const float  fExpectedCameraHeightFromFloorTolerance = constants::ZED_DEFAULT_FLOOR_PLANE_ERROR)
overridevirtual

This method is used to enable positional tracking on the camera. Since this is a simulation camera, this method will just set the member variable and then use the NavBoard to simulate the camera's position.

Parameters
fExpectedCameraHeightFromFloorTolerance- The expected camera height from the floor tolerance.
Returns
sl::ERROR_CODE - The error code returned by the ZED SDK. In this case, it will always be SUCCESS.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-26

Implements ZEDCamera.

852{
853 // Unused parameter.
854 (void) fExpectedCameraHeightFromFloorTolerance;
855 // Update member variables.
856 m_bCameraPositionalTrackingEnabled = true;
857
858 return sl::ERROR_CODE::SUCCESS;
859}
Here is the caller graph for this function:

◆ DisablePositionalTracking()

void SIMZEDCam::DisablePositionalTracking ( )
overridevirtual

This method is used to disable positional tracking on the camera. Since this is a simulation camera, this method will just set the member variable.

Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-26

Implements ZEDCamera.

870{
871 // Update member variables.
872 m_bCameraPositionalTrackingEnabled = false;
873}
Here is the caller graph for this function:

◆ SetPositionalPose()

void SIMZEDCam::SetPositionalPose ( const double  dX,
const double  dY,
const double  dZ,
const double  dXO,
const double  dYO,
const double  dZO 
)
overridevirtual

This method is used to set the positional pose of the camera. Since this is a simulation camera, this method will just set the offset member variables.

Parameters
dX- The new X position of the camera in ZED_MEASURE_UNITS.
dY- The new Y position of the camera in ZED_MEASURE_UNITS.
dZ- The new Z position of the camera in ZED_MEASURE_UNITS.
dXO- The new tilt of the camera around the X axis in degrees.
dYO- The new tilt of the camera around the Y axis in degrees.
dZO- The new tilt of the camera around the Z axis in degrees.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-26

Implements ZEDCamera.

890{
891 // Acquire lock on the current rover pose mutex.
892 std::unique_lock<std::shared_mutex> lkPose(m_muCurrentRoverPoseMutex);
893
894 // Update offset member variables.
895 m_dPoseOffsetX = dX - m_stCurrentRoverPose.GetUTMCoordinate().dEasting;
896 m_dPoseOffsetY = dY - m_stCurrentRoverPose.GetUTMCoordinate().dAltitude;
897 m_dPoseOffsetZ = dZ - m_stCurrentRoverPose.GetUTMCoordinate().dNorthing;
898 m_dPoseOffsetXO = dXO;
899 m_dPoseOffsetYO = dYO - m_stCurrentRoverPose.GetCompassHeading();
900 m_dPoseOffsetZO = dZO;
901}
double GetCompassHeading() const
Accessor for the Compass Heading private member.
Definition GeospatialOperations.hpp:787
const geoops::UTMCoordinate & GetUTMCoordinate() const
Accessor for the geoops::UTMCoordinate member variable.
Definition GeospatialOperations.hpp:767
Here is the call graph for this function:

◆ GetCameraIsOpen()

bool SIMZEDCam::GetCameraIsOpen ( )
overridevirtual

Accessor for the camera open status.

Returns
true - The camera has been successfully opened.
false - The camera has not been successfully opened.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-09-30

Implements Camera< cv::Mat >.

913{
914 return m_pRGBStream->GetIsConnected() && m_pDepthImageStream->GetIsConnected() && this->GetThreadState() == AutonomyThreadState::eRunning;
915}
AutonomyThreadState GetThreadState() const
Accessor for the Threads State private member.
Definition AutonomyThread.hpp:214
Here is the call graph for this function:
Here is the caller graph for this function:

◆ GetUsingGPUMem()

bool SIMZEDCam::GetUsingGPUMem ( ) const
overridevirtual

Returns if the camera is using GPU memory. This is a simulation camera, so this method will always return false.

Returns
true - We are using GPU memory.
false - We are not using GPU memory.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-26

Reimplemented from ZEDCamera.

928{
929 return false;
930}

◆ GetCameraModel()

std::string SIMZEDCam::GetCameraModel ( )
overridevirtual

Accessor for the name of this model of camera.

Returns
std::string - The model of the camera.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-26

Implements ZEDCamera.

941{
942 return "SIMZED2i";
943}

◆ GetPositionalTrackingEnabled()

bool SIMZEDCam::GetPositionalTrackingEnabled ( )
overridevirtual

Accessor for the if the camera's positional tracking is enabled. Since this is a simulation camera, this method will just return the member variable.

Returns
true - Positional tracking is enabled.
false - Positional tracking is disabled.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-26

Implements ZEDCamera.

956{
957 return m_bCameraPositionalTrackingEnabled && this->GetCameraIsOpen();
958}
bool GetCameraIsOpen() override
Accessor for the camera open status.
Definition SIMZEDCam.cpp:912
Here is the call graph for this function:
Here is the caller graph for this function:

◆ ThreadedContinuousCode()

void SIMZEDCam::ThreadedContinuousCode ( )
overrideprivatevirtual

The code inside this private method runs in a separate thread, but still has access to this*. This method continuously get new frames from the OpenCV VideoCapture object and stores it in a member variable. Then a thread pool is started and joined once per iteration to mass copy the frames and/or measure to any other thread waiting in the queues.

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

Implements AutonomyThread< void >.

275{
276 // Acquire a lock on the rover pose mutex.
277 std::unique_lock<std::shared_mutex> lkRoverPoseLock(m_muCurrentRoverPoseMutex);
278 // Check if the NavBoard pointer is valid.
279 if (globals::g_pNavigationBoard != nullptr)
280 {
281 // Get the current rover pose from the NavBoard.
282 m_stCurrentRoverPose = geoops::RoverPose(globals::g_pNavigationBoard->GetGPSData(), globals::g_pNavigationBoard->GetHeading());
283 }
284 // Release lock.
285 lkRoverPoseLock.unlock();
286
287 // Check if the depth image WebRTC connection is open.
288 if (m_pDepthImageStream != nullptr && m_pDepthImageStream->GetIsConnected())
289 {
290 // Acquire a lock on the WebRTC mutex.
291 std::shared_lock<std::shared_mutex> lkWebRTC2(m_muWebRTCDepthImageCopyMutex);
292 // Estimate the depth measure from the depth image.
293 this->EstimateDepthMeasure(m_cvDepthImage, m_cvDepthMeasure);
294 // Check if the depth image is empty.
295 if (m_cvDepthImage.empty())
296 {
297 // Release lock.
298 lkWebRTC2.unlock();
299 return;
300 }
301 // Release lock.
302 lkWebRTC2.unlock();
303
304 // Calculate the point cloud from the estimated depth measure.
305 this->CalculatePointCloud(m_cvDepthMeasure, m_cvPointCloud);
306 }
307
308 // Acquire a shared_lock on the frame copy queue.
309 std::shared_lock<std::shared_mutex> lkSchedulers(m_muPoolScheduleMutex);
310 // Check if the frame copy queue is empty.
311 if (!m_qFrameCopySchedule.empty() || !m_qPoseCopySchedule.empty() || !m_qGeoPoseCopySchedule.empty() || !m_qSensorsCopySchedule.empty())
312 {
313 // Add the length of all queues together to determine the number of tasks to create.
314 size_t siTotalQueueLength = m_qFrameCopySchedule.size() + m_qPoseCopySchedule.size() + m_qGeoPoseCopySchedule.size() + m_qSensorsCopySchedule.size();
315
316 // Acquire shared lock on the WebRTC mutex, so that the WebRTC connection doesn't try to write to the Mats while they are being copied in the thread pool.
317 std::shared_lock<std::shared_mutex> lkWebRTC(m_muWebRTCRGBImageCopyMutex);
318 std::shared_lock<std::shared_mutex> lkWebRTC2(m_muWebRTCDepthImageCopyMutex);
319
320 // Start the thread pool to store multiple copies of the sl::Mat into the given cv::Mats.
321 this->RunDetachedPool(siTotalQueueLength, m_nNumFrameRetrievalThreads);
322
323 // Static bool for keeping track of if the thread pool has been started.
324 static bool bQueueTogglesAlreadyReset = false;
325 // Get current time.
326 std::chrono::_V2::system_clock::duration tmCurrentTime = std::chrono::high_resolution_clock::now().time_since_epoch();
327 // Only reset once every couple seconds.
328 if (std::chrono::duration_cast<std::chrono::seconds>(tmCurrentTime).count() % 31 == 0 && !bQueueTogglesAlreadyReset)
329 {
330 // Reset queue counters.
331 m_bPosesQueued.store(false, ATOMIC_MEMORY_ORDER_METHOD);
332 m_bGeoPosesQueued.store(false, ATOMIC_MEMORY_ORDER_METHOD);
333 m_bSensorsQueued.store(false, ATOMIC_MEMORY_ORDER_METHOD);
334
335 // Set reset toggle.
336 bQueueTogglesAlreadyReset = true;
337 }
338 // Crucial for toggle action. If time is not evenly devisable and toggles have previously been set, reset queue reset boolean.
339 else if (bQueueTogglesAlreadyReset)
340 {
341 // Reset reset toggle.
342 bQueueTogglesAlreadyReset = false;
343 }
344
345 // Wait for thread pool to finish.
346 this->JoinPool();
347
348 // Release lock on WebRTC mutex.
349 lkWebRTC.unlock();
350 lkWebRTC2.unlock();
351 }
352
353 // Release lock on frame copy queue.
354 lkSchedulers.unlock();
355}
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 CalculatePointCloud(const cv::Mat &cvDepthMeasure, cv::Mat &cvPointCloud)
This method calculates a point cloud from the decoded depth measure use some simple trig and the came...
Definition SIMZEDCam.cpp:222
void EstimateDepthMeasure(const cv::Mat &cvDepthImage, cv::Mat &cvDepthMeasure)
This method estimates the depth measure from the depth image.
Definition SIMZEDCam.cpp:175
bool empty() const
This struct is used by the WaypointHandler to provide an easy way to store all pose data about the ro...
Definition GeospatialOperations.hpp:708
Here is the call graph for this function:

◆ PooledLinearCode()

void SIMZEDCam::PooledLinearCode ( )
overrideprivatevirtual

This method holds the code that is ran in the thread pool started by the ThreadedLinearCode() method. It copies the data from the different data objects to references of the same type stored in a vector queued up by the Grab methods.

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

Implements AutonomyThread< void >.

368{
370 // Frame queue.
372
373 // Acquire mutex for getting frames out of the queue.
374 std::unique_lock<std::shared_mutex> lkFrameQueue(m_muFrameCopyMutex);
375 // Check if the queue is empty.
376 if (!m_qFrameCopySchedule.empty())
377 {
378 // Get frame container out of queue.
379 containers::FrameFetchContainer<cv::Mat> stContainer = m_qFrameCopySchedule.front();
380 // Pop out of queue.
381 m_qFrameCopySchedule.pop();
382 // Release lock.
383 lkFrameQueue.unlock();
384
385 // Determine which frame should be copied.
386 switch (stContainer.eFrameType)
387 {
388 case PIXEL_FORMATS::eBGRA: *(stContainer.pFrame) = m_cvFrame.clone(); break;
389 case PIXEL_FORMATS::eDepthImage: *(stContainer.pFrame) = m_cvDepthImage.clone(); break;
390 case PIXEL_FORMATS::eDepthMeasure: *(stContainer.pFrame) = m_cvDepthMeasure.clone(); break;
391 case PIXEL_FORMATS::eXYZ: *(stContainer.pFrame) = m_cvPointCloud.clone(); break;
392 default: *(stContainer.pFrame) = m_cvFrame.clone(); break;
393 }
394
395 // Signal future that the frame has been successfully retrieved.
396 stContainer.pCopiedFrameStatus->set_value(true);
397 }
398
400 // Pose queue.
402 // Acquire mutex for getting data out of the pose queue.
403 std::unique_lock<std::shared_mutex> lkPoseQueue(m_muPoseCopyMutex);
404 // Check if the queue is empty.
405 if (!m_qPoseCopySchedule.empty())
406 {
407 // Get pose container out of queue.
408 containers::DataFetchContainer<Pose> stContainer = m_qPoseCopySchedule.front();
409 // Pop out of queue.
410 m_qPoseCopySchedule.pop();
411 // Release lock.
412 lkPoseQueue.unlock();
413
414 // Get angle realignments.
415 double dNewYO = numops::InputAngleModulus<double>(m_stCurrentRoverPose.GetCompassHeading() + m_dPoseOffsetYO, 0.0, 360.0);
416 // Repack values into pose.
417 Pose stPose(m_stCurrentRoverPose.GetUTMCoordinate().dEasting + m_dPoseOffsetX,
418 m_stCurrentRoverPose.GetUTMCoordinate().dAltitude + m_dPoseOffsetY,
419 m_stCurrentRoverPose.GetUTMCoordinate().dNorthing + m_dPoseOffsetZ,
420 m_dPoseOffsetXO,
421 dNewYO,
422 m_dPoseOffsetZO);
423
424 // ISSUE NOTE: Might be in the future if we ever change our coordinate system on the ZED. This can be used to fix the directions of the Pose's coordinate system.
425 // // Check ZED coordinate system.
426 // switch (m_slCameraParams.coordinate_system)
427 // {
428 // case sl::COORDINATE_SYSTEM::LEFT_HANDED_Y_UP:
429 // {
430 // // Realign based in the signedness of this coordinate system. Z is backwards.
431 // stPose.stTranslation.dZ *= -1;
432 // break;
433 // }
434 // default:
435 // {
436 // // No need to flip signs for other coordinate systems.
437 // break;
438 // }
439 // }
440
441 // Copy pose.
442 *(stContainer.pData) = stPose;
443
444 // Signal future that the data has been successfully retrieved.
445 stContainer.pCopiedDataStatus->set_value(true);
446 }
447 else
448 {
449 // Release lock.
450 lkPoseQueue.unlock();
451 }
452
454 // GeoPose queue.
456 // Acquire mutex for getting data out of the pose queue.
457 std::unique_lock<std::shared_mutex> lkGeoPoseQueue(m_muGeoPoseCopyMutex);
458 // Check if the queue is empty.
459 if (!m_qGeoPoseCopySchedule.empty())
460 {
461 // Get pose container out of queue.
462 containers::DataFetchContainer<sl::GeoPose> stContainer = m_qGeoPoseCopySchedule.front();
463 // Pop out of queue.
464 m_qGeoPoseCopySchedule.pop();
465 // Release lock.
466 lkGeoPoseQueue.unlock();
467
468 // Get rover's current UTM position.
469 geoops::UTMCoordinate stCurrentUTM = m_stCurrentRoverPose.GetUTMCoordinate();
470 // Add offsets to the current UTM position.
471 stCurrentUTM.dEasting += m_dPoseOffsetX;
472 stCurrentUTM.dAltitude += m_dPoseOffsetY;
473 stCurrentUTM.dNorthing += m_dPoseOffsetZ;
474 // Create a GPS coordinate from the UTM position.
475 geoops::GPSCoordinate stCurrentGPS = geoops::ConvertUTMToGPS(stCurrentUTM);
476
477 // Create new GeoPose.
478 sl::GeoPose slGeoPose;
479 slGeoPose.heading = numops::InputAngleModulus<double>(m_stCurrentRoverPose.GetCompassHeading() + m_dPoseOffsetYO, 0.0, 360.0);
480 slGeoPose.latlng_coordinates.setCoordinates(stCurrentGPS.dLatitude, stCurrentGPS.dLongitude, stCurrentGPS.dAltitude, false);
481
482 // Copy pose.
483 *(stContainer.pData) = slGeoPose;
484
485 // Signal future that the data has been successfully retrieved.
486 stContainer.pCopiedDataStatus->set_value(true);
487 }
488 else
489 {
490 // Release lock.
491 lkGeoPoseQueue.unlock();
492 }
493
495 // Sensors queue.
497 // Acquire mutex for getting data out of the sensors queue.
498 std::unique_lock<std::shared_mutex> lkSensorsQueue(m_muSensorsCopyMutex);
499 // Check if the queue is empty.
500 if (!m_qSensorsCopySchedule.empty())
501 {
502 // Get pose container out of queue.
503 containers::DataFetchContainer<sl::SensorsData> stContainer = m_qSensorsCopySchedule.front();
504 // Pop out of queue.
505 m_qSensorsCopySchedule.pop();
506 // Release lock.
507 lkSensorsQueue.unlock();
508
509 // Copy pose.
510 *(stContainer.pData) = m_stIMUData;
511
512 // Signal future that the data has been successfully retrieved.
513 stContainer.pCopiedDataStatus->set_value(true);
514 }
515 else
516 {
517 // Release lock.
518 lkSensorsQueue.unlock();
519 }
520}
CV_NODISCARD_STD Mat clone() const
GPSCoordinate ConvertUTMToGPS(const UTMCoordinate &stUTMCoord)
Given a UTM coordinate, convert to GPS and create a new GPSCoordinate object.
Definition GeospatialOperations.hpp:378
This struct stores/contains information about a GPS data.
Definition GeospatialOperations.hpp:100
This struct stores/contains information about a UTM coordinate.
Definition GeospatialOperations.hpp:211
Here is the call graph for this function:

◆ SetCallbacks()

void SIMZEDCam::SetCallbacks ( )
private

This method sets the callbacks for the WebRTC connections.

Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-26
136{
137 // Set the frame callbacks.
138 m_pRGBStream->SetOnFrameReceivedCallback(
139 [this](cv::Mat& cvFrame)
140 {
141 // Check if the frame is empty.
142 if (!cvFrame.empty())
143 {
144 // Acquire a lock on the webRTC copy mutex.
145 std::unique_lock<std::shared_mutex> lkWebRTC(m_muWebRTCRGBImageCopyMutex);
146 // Deep copy the frame.
147 m_cvFrame = cvFrame.clone();
148 }
149 });
150 m_pDepthImageStream->SetOnFrameReceivedCallback(
151 [this](cv::Mat& cvFrame)
152 {
153 // Check if the frame is empty.
154 if (!cvFrame.empty())
155 {
156 // Acquire a lock on the webRTC copy mutex.
157 std::unique_lock<std::shared_mutex> lkWebRTC(m_muWebRTCDepthImageCopyMutex);
158 // Deep copy the frame to the depth image buffer.
159 m_cvDepthImageBuffer = cvFrame.clone();
160 // Convert the depth image buffer to grayscale.
161 cv::cvtColor(m_cvDepthImageBuffer, m_cvDepthImage, cv::COLOR_BGR2GRAY);
162 }
163 });
164}
Here is the call graph for this function:
Here is the caller graph for this function:

◆ EstimateDepthMeasure()

void SIMZEDCam::EstimateDepthMeasure ( const cv::Mat cvDepthImage,
cv::Mat cvDepthMeasure 
)
private

This method estimates the depth measure from the depth image.

Parameters
cvDepthImage- The depth image to estimate the depth measure from.
cvDepthMeasure- The estimated depth measure that will be written to.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2025-04-29
176{
177 // Declare instance variables.
178 const float fMaxDepth = 2001.0f; // Maximum depth in cm.
179
180 // Check if the depth image is empty.
181 if (cvDepthImage.empty())
182 {
183 // If the depth image is empty, fill the depth measure with zeros.
184 cvDepthMeasure = cv::Mat::zeros(cvDepthMeasure.size(), CV_32FC1);
185 return;
186 }
187
188// TEST: Even though this speeds up the code, it might be too much CPU work as the codebase grows. Use a GpuMat instead.
189#pragma omp parallel for collapse(2)
190
191 // Iterate over each pixel in the cvDepthImage image.
192 for (int nY = 0; nY < cvDepthImage.rows; ++nY)
193 {
194 for (int nX = 0; nX < cvDepthImage.cols; ++nX)
195 {
196 // For this, we are just using the depth image to estimate the depth measure. We will treat 255 as 0 cm and 0 as fMaxDepth - 1 cm.
197 // Get the depth value from the depth image.
198 uchar ucDepthValue = cvDepthImage.at<uchar>(nY, nX);
199
200 // Calculate the depth in cm.
201 float fDepth = (1.0f - (ucDepthValue / 255.0f)) * fMaxDepth;
202 // Check if nY and nX are within the bounds of the depth measure image.
203 if (nY < cvDepthMeasure.rows && nX < cvDepthMeasure.cols)
204 {
205 // Store the estimated depth in the new cv::Mat. Convert cm to m.
206 cvDepthMeasure.at<float>(nY, nX) = fDepth / 100.0f; // Convert cm to m.
207 }
208 }
209 }
210}
MatSize size
_Tp & at(int i0=0)
unsigned char uchar
Here is the call graph for this function:
Here is the caller graph for this function:

◆ CalculatePointCloud()

void SIMZEDCam::CalculatePointCloud ( const cv::Mat cvDepthMeasure,
cv::Mat cvPointCloud 
)
private

This method calculates a point cloud from the decoded depth measure use some simple trig and the camera FOV.

Parameters
cvDepthMeasure- The decoded depth measure.
cvPointCloud- The point cloud that will be written to.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2025-01-04
223{
224 // Calculate focal lengths from FOV.
225 const double dRadPerDeg = M_PI / 180.0;
226 const double dFx = (cvDepthMeasure.cols / 2.0) / tan(m_dPropHorizontalFOV * dRadPerDeg / 2.0);
227 const double dFy = (cvDepthMeasure.rows / 2.0) / tan(m_dPropVerticalFOV * dRadPerDeg / 2.0);
228 // Image center.
229 const double dCx = cvDepthMeasure.cols / 2.0;
230 const double dCy = cvDepthMeasure.rows / 2.0;
231
232// TEST: Even though this speeds up the code, it might be too much CPU work as the codebase grows. Use a GpuMat instead.
233// This is a parallel for loop that calculates the point cloud from the decoded depth measure.
234#pragma omp parallel for collapse(2)
235
236 // Iterate over each pixel in the cvDepthMeasure image.
237 for (int nY = 0; nY < cvDepthMeasure.rows; ++nY)
238 {
239 for (int nX = 0; nX < cvDepthMeasure.cols; ++nX)
240 {
241 // Get depth value.
242 float fDepth = cvDepthMeasure.at<float>(nY, nX);
243
244 // Skip invalid depth values.
245 if (fDepth <= 0)
246 {
247 cvPointCloud.at<cv::Vec4f>(nY, nX) = cv::Vec4f(0, 0, 0, 0);
248 continue;
249 }
250
251 // Convert from pixel coordinates to 3D coordinates.
252 float fX = static_cast<float>((nX - dCx) * fDepth / dFx);
253 float fY = static_cast<float>((dCy - nY) * fDepth / dFy);
254 float fZ = fDepth;
255
256 // Store point. (XYZ + intensity, using Y channel for intensity)
257 cvPointCloud.at<cv::Vec4f>(nY, nX) = cv::Vec4f(fX, fY, fZ, 255);
258 }
259 }
260}
__device__ __forceinline__ float3 tan(const uchar3 &a)
Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ ProcessIMUData

const std::function<void(const rovecomm::RoveCommPacket<double>&, const sockaddr_in&)> SIMZEDCam::ProcessIMUData
private

Callback function to process incoming IMU data from RoveComm for the SIM ZED Camera. Normally, this data would come from the physical ZED camera's IMU over USB,.

Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2025-11-19
101 {
102 // Not using this.
103 (void) stdAddr;
104
105 // Acquire a write lock on the sensors mutex.
106 std::unique_lock<std::shared_mutex> lkSensorsProcessLock(m_muSensorsCopyMutex);
107 // Update IMU data.
108 m_stIMUData.imu.linear_acceleration.x = static_cast<float>(stPacket.vData[0]);
109 m_stIMUData.imu.linear_acceleration.y = static_cast<float>(stPacket.vData[1]);
110 m_stIMUData.imu.linear_acceleration.z = static_cast<float>(stPacket.vData[2]);
111 m_stIMUData.imu.angular_velocity.x = static_cast<float>(stPacket.vData[3]);
112 m_stIMUData.imu.angular_velocity.y = static_cast<float>(stPacket.vData[4]);
113 m_stIMUData.imu.angular_velocity.z = static_cast<float>(stPacket.vData[5]);
114
115 // Manually calculate the Gyro pose using the Tait-Bryan angles (ZYX convention) and the quaternion representation.
116 // This is because the SIM does not provide orientation data from the IMU, only angular velocity.
117 double dQx = stPacket.vData[6];
118 double dQy = stPacket.vData[7];
119 double dQz = stPacket.vData[8];
120 double dQw = stPacket.vData[9];
121 double dRoll = std::atan2(2.0 * (dQw * dQx + dQy * dQz), 1.0 - 2.0 * (dQx * dQx + dQy * dQy));
122 double dPitch = std::asin(2.0 * (dQw * dQy - dQz * dQx));
123 double dYaw = std::atan2(2.0 * (dQw * dQz + dQx * dQy), 1.0 - 2.0 * (dQy * dQy + dQz * dQz));
124 // Pack the gyro values into a sl::Transform.
125 sl::float3 slEulerAngles(static_cast<float>(dRoll), static_cast<float>(dPitch), static_cast<float>(dYaw));
126 sl::Transform slIMUTransform;
127 slIMUTransform.setEulerAngles(slEulerAngles);
128 m_stIMUData.imu.pose = slIMUTransform;
129
130 // Unlock mutex.
131 lkSensorsProcessLock.unlock();
132
133 // Submit logger message.
134 LOG_DEBUG(logging::g_qSharedLogger,
135 "Incoming IMU data processed from RoveComm for SIM ZED Camera: (AccelX {}, AccelY {}, AccelZ {}, GyroX {}, GyroY {}, GyroZ {})",
136 stPacket.vData[0],
137 stPacket.vData[1],
138 stPacket.vData[2],
139 stPacket.vData[3],
140 stPacket.vData[4],
141 stPacket.vData[5]);
142 };

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