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
ZEDCamera Class Referenceabstract

This class serves as a middle inheritor between the Camera interface and the ZEDCam class. ZEDCam and SIMZEDCam will inherit from this class. More...

#include <ZEDCamera.hpp>

Inheritance diagram for ZEDCamera:
Collaboration diagram for ZEDCamera:

Classes

struct  Pose
 This struct is used within the ZEDCam class to store the camera pose with high precision. The sl::Pose object from the ZEDSDK stores everything as float which is not precise enough for storing relative UTM values. This struct replaces that. More...
 
struct  ZedObjectData
 This struct is part of the ZEDCam class and is used as a container for all bounding box data that is going to be passed to the zed api via the ZEDCam's TrackCustomBoxObjects() method. More...
 

Public Member Functions

 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.
 
std::future< bool > RequestFrameCopy (cv::Mat &cvFrame) override=0
 
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::Mat &cvDepth, const bool bRetrieveMeasure=true)=0
 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 > 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::Mat &cvPointCloud)=0
 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 > 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 sl::ERROR_CODE ResetPositionalTracking ()=0
 Resets the positional tracking of the camera.
 
virtual sl::ERROR_CODE TrackCustomBoxObjects (std::vector< ZedObjectData > &vCustomObjects)
 Tracks custom bounding boxes in the camera's field of view.
 
virtual sl::ERROR_CODE RebootCamera ()=0
 Reboots the camera.
 
virtual sl::FUSION_ERROR_CODE SubscribeFusionToCameraUUID (sl::CameraIdentifier &slCameraUUID)=0
 Subscribes the fusion object to the camera with the given UUID.
 
virtual sl::CameraIdentifier PublishCameraToFusion ()=0
 Publishes the camera to the fusion object.
 
virtual sl::FUSION_ERROR_CODE IngestGPSDataToFusion (geoops::GPSCoordinate stNewGPSLocation)
 Ingests GPS data into the fusion object.
 
virtual sl::ERROR_CODE EnablePositionalTracking (const float fExpectedCameraHeightFromFloorTolerance=constants::ZED_DEFAULT_FLOOR_PLANE_ERROR)=0
 Enables the position tracking of the camera.
 
virtual void DisablePositionalTracking ()=0
 Disables the position tracking of the camera.
 
virtual void SetPositionalPose (const double dX, const double dY, const double dZ, const double dXO, const double dYO, const double dZO)=0
 Mutator for the Positional Pose private member.
 
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 GetUsingGPUMem () const
 Accessor for the Using G P U Memory private member.
 
virtual bool GetIsFusionMaster () const
 Accessor for if this ZED is running a fusion instance.
 
virtual std::string GetCameraModel ()=0
 Accessor for the Camera Model private member.
 
virtual unsigned int GetCameraSerial ()
 Accessor for the Camera Serial private member.
 
virtual std::future< bool > RequestPositionalPoseCopy (Pose &stPose)=0
 Puts a Pose pointer into a queue so a copy of a Pose from the camera can be written to it.
 
virtual std::future< bool > RequestFusionGeoPoseCopy (sl::GeoPose &slGeoPose)=0
 Puts a GeoPose pointer into a queue so a copy of a GeoPose 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 bool GetPositionalTrackingEnabled ()=0
 Accessor for the Positional Tracking Enabled 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.
 
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.
 
- 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.
 
virtual bool GetCameraIsOpen ()=0
 Accessor for the Camera Is Open 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.
 

Protected Attributes

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
 

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.
 

Detailed Description

This class serves as a middle inheritor between the Camera interface and the ZEDCam class. ZEDCam and SIMZEDCam will inherit from this class.

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

Constructor & Destructor Documentation

◆ ZEDCamera()

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 
)
inline

Construct a new ZEDCamera object.

Parameters
nPropResolutionX- The X resolution of the camera.
nPropResolutionY- The Y resolution of the camera.
nPropFramesPerSecond- The FPS of the camera.
dPropHorizontalFOV- The horizontal field of view.
dPropVerticalFOV- The vertical field of view.
bEnableRecordingFlag- Whether or not this camera should be recorded.
fMinSenseDistance- The minimum distance the camera can sense.
fMaxSenseDistance- The maximum distance the camera can sense.
bMemTypeGPU- Whether or not to use GPU memory.
bUseHalfDepthPrecision- Whether or not to use half depth precision.
bEnableFusionMaster- Whether or not to enable the fusion master.
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
2024-12-22
161 :
162 Camera(nPropResolutionX,
163 nPropResolutionY,
164 nPropFramesPerSecond,
165 PIXEL_FORMATS::eZED,
166 dPropHorizontalFOV,
167 dPropVerticalFOV,
168 bEnableRecordingFlag,
169 nNumFrameRetrievalThreads)
170 {
171 // Initialize member variables. Some parameters are not used.
172 (void) bMemTypeGPU;
173 (void) bUseHalfDepthPrecision;
174 (void) bEnableFusionMaster;
175 m_bCameraIsFusionMaster = bEnableFusionMaster;
176 m_unCameraSerialNumber = unCameraSerialNumber;
177 }
This interface class serves as a base for all other classes that will implement and interface with a ...
Definition Camera.hpp:34

◆ ~ZEDCamera()

virtual ZEDCamera::~ZEDCamera ( )
virtualdefault

Destroy the ZEDCamera object.

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

Member Function Documentation

◆ RequestFrameCopy() [1/2]

std::future< bool > ZEDCamera::RequestFrameCopy ( cv::Mat cvFrame)
overridepure virtual

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
2024-12-22

Implements Camera< cv::Mat >.

Implemented in SIMZEDCam, and ZEDCam.

◆ RequestFrameCopy() [2/2]

virtual std::future< bool > ZEDCamera::RequestFrameCopy ( cv::cuda::GpuMat cvGPUFrame)
inlinevirtual

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

Parameters
cvGPUFrame- A reference to the cv::cuda::GpuMat to store the frame in.
Returns
std::future<bool> - A future that should be waited on before the passed in frame 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-22

Reimplemented in ZEDCam.

211 {
212 // Create instance variables.
213 (void) cvGPUFrame;
214 std::promise<bool> pmPromise;
215 std::future<bool> fuFuture = pmPromise.get_future();
216
217 // Immediately set the promise to false.
218 pmPromise.set_value(false);
219
220 // Submit logger message.
221 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::RequestFrameCopy(cv::cuda::GpuMat& cvGPUFrame) not implemented. If SIM_MODE use cv::Mat version instead.");
222
223 return fuFuture;
224 }

◆ RequestDepthCopy() [1/2]

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

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

Parameters
cvDepth- A reference to the cv::Mat to store the depth frame in.
bRetrieveMeasure- Whether or not to retrieve the depth measure or just the image.
Returns
std::future<bool> - A future that should be waited on before the passed in frame 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-22

Implemented in SIMZEDCam, and ZEDCam.

◆ RequestDepthCopy() [2/2]

virtual std::future< bool > ZEDCamera::RequestDepthCopy ( cv::cuda::GpuMat cvGPUDepth,
const bool  bRetrieveMeasure = true 
)
inlinevirtual

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

Parameters
cvGPUDepth- A reference to the cv::cuda::GpuMat to store the depth frame in.
bRetrieveMeasure- Whether or not to retrieve the depth measure or just the image.
Returns
std::future<bool> - A future that should be waited on before the passed in frame 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-22

Reimplemented in ZEDCam.

249 {
250 // Initialize instance variables.
251 (void) cvGPUDepth;
252 (void) bRetrieveMeasure;
253 std::promise<bool> pmPromise;
254
255 // Immediately set the promise to false.
256 pmPromise.set_value(false);
257
258 // Submit logger message.
259 LOG_ERROR(logging::g_qSharedLogger,
260 "ZEDCamera::RequestDepthCopy(cv::cuda::GpuMat& cvGPUDepth, const bool bRetrieveMeasure = true) not implemented. If SIM_MODE use cv::Mat version "
261 "instead.");
262
263 return pmPromise.get_future();
264 }

◆ RequestPointCloudCopy() [1/2]

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

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

Parameters
cvPointCloud- A reference to the cv::Mat to store the point cloud in.
Returns
std::future<bool> - A future that should be waited on before the passed in frame 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-22

Implemented in SIMZEDCam, and ZEDCam.

◆ RequestPointCloudCopy() [2/2]

virtual std::future< bool > ZEDCamera::RequestPointCloudCopy ( cv::cuda::GpuMat cvGPUPointCloud)
inlinevirtual

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

Parameters
cvGPUPointCloud- A reference to the cv::cuda::GpuMat to store the point cloud in.
Returns
std::future<bool> - A future that should be waited on before the passed in frame 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-25

Reimplemented in ZEDCam.

287 {
288 // Initialize instance variables.
289 (void) cvGPUPointCloud;
290 std::promise<bool> pmPromise;
291
292 // Immediately set the promise to false.
293 pmPromise.set_value(false);
294
295 // Submit logger message.
296 LOG_ERROR(logging::g_qSharedLogger,
297 "ZEDCamera::RequestPointCloudCopy(cv::cuda::GpuMat& cvGPUPointCloud) not implemented. If SIM_MODE use cv::Mat version instead.");
298
299 return pmPromise.get_future();
300 }

◆ ResetPositionalTracking()

virtual sl::ERROR_CODE ZEDCamera::ResetPositionalTracking ( )
pure virtual

Resets the positional tracking of the camera.

Returns
sl::ERROR_CODE - The error code returned by the ZED SDK.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-25

Implemented in SIMZEDCam, and ZEDCam.

◆ TrackCustomBoxObjects()

virtual sl::ERROR_CODE ZEDCamera::TrackCustomBoxObjects ( std::vector< ZedObjectData > &  vCustomObjects)
inlinevirtual

Tracks custom bounding boxes in the camera's field of view.

Parameters
vCustomBoxes- A vector of ZedObjectData structs representing the custom bounding boxes to track.
Returns
sl::ERROR_CODE - The error code returned by the ZED SDK.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-25

Reimplemented in ZEDCam.

322 {
323 // Initialize instance variables.
324 (void) vCustomObjects;
325
326 // Submit logger message.
327 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::TrackCustomBoxObjects(const std::vector<ZedObjectData>& vCustomObjects) not implemented.");
328
329 return sl::ERROR_CODE::FAILURE;
330 }

◆ RebootCamera()

virtual sl::ERROR_CODE ZEDCamera::RebootCamera ( )
pure virtual

Reboots the camera.

Returns
sl::ERROR_CODE - The error code returned by the ZED SDK.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-25

Implemented in SIMZEDCam, and ZEDCam.

◆ SubscribeFusionToCameraUUID()

virtual sl::FUSION_ERROR_CODE ZEDCamera::SubscribeFusionToCameraUUID ( sl::CameraIdentifier &  slCameraUUID)
pure virtual

Subscribes the fusion object to the camera with the given UUID.

Parameters
slCameraUUID- The UUID of the camera to subscribe to.
Returns
sl::FUSION_ERROR_CODE - The error code returned by the ZED SDK.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-25

Implemented in SIMZEDCam, and ZEDCam.

◆ PublishCameraToFusion()

virtual sl::CameraIdentifier ZEDCamera::PublishCameraToFusion ( )
pure virtual

Publishes the camera to the fusion object.

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-25

Implemented in SIMZEDCam, and ZEDCam.

◆ IngestGPSDataToFusion()

virtual sl::FUSION_ERROR_CODE ZEDCamera::IngestGPSDataToFusion ( geoops::GPSCoordinate  stNewGPSLocation)
inlinevirtual

Ingests GPS data into the fusion object.

Parameters
stNewGPSLocation- The new GPS location to ingest.
Returns
sl::FUSION_ERROR_CODE - The error code returned by the ZED SDK.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-25

Reimplemented in ZEDCam.

373 {
374 // Initialize instance variables.
375 (void) stNewGPSLocation;
376
377 // Submit logger message.
378 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::IngestGPSDataToFusion(geoops::GPSCoordinate stNewGPSLocation) not implemented.");
379
380 return sl::FUSION_ERROR_CODE::FAILURE;
381 }

◆ EnablePositionalTracking()

virtual sl::ERROR_CODE ZEDCamera::EnablePositionalTracking ( const float  fExpectedCameraHeightFromFloorTolerance = constants::ZED_DEFAULT_FLOOR_PLANE_ERROR)
pure virtual

Enables the position tracking of the camera.

Parameters
fExpectedCameraHeightFromFloorTolerance- The expected camera height from the floor tolerance.
Returns
sl::ERROR_CODE - The error code returned by the ZED SDK.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-25

Implemented in SIMZEDCam, and ZEDCam.

◆ DisablePositionalTracking()

virtual void ZEDCamera::DisablePositionalTracking ( )
pure virtual

Disables the position tracking 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-25

Implemented in SIMZEDCam, and ZEDCam.

◆ SetPositionalPose()

virtual void ZEDCamera::SetPositionalPose ( const double  dX,
const double  dY,
const double  dZ,
const double  dXO,
const double  dYO,
const double  dZO 
)
pure virtual

Mutator for the Positional Pose private member.

Parameters
dX- The X position of the camera in ZED_MEASURE_UNITS.
dY- The Y position of the camera in ZED_MEASURE_UNITS.
dZ- The Z position of the camera in ZED_MEASURE_UNITS.
dXO- The tilt of the camera around the X axis in degrees.
dYO- The tilt of the camera around the Y axis in degrees.
dZO- The 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-25

Implemented in SIMZEDCam, and ZEDCam.

◆ EnableSpatialMapping()

virtual sl::ERROR_CODE ZEDCamera::EnableSpatialMapping ( )
inlinevirtual

Enables spatial mapping.

Returns
sl::ERROR_CODE - The error code returned by the ZED SDK.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-25

Reimplemented in ZEDCam.

431 {
432 // Submit logger message.
433 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::EnableSpatialMapping() not implemented.");
434
435 return sl::ERROR_CODE::FAILURE;
436 }

◆ DisableSpatialMapping()

virtual void ZEDCamera::DisableSpatialMapping ( )
inlinevirtual

Disables spatial mapping.

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

Reimplemented in ZEDCam.

446 {
447 // Submit logger message.
448 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::DisableSpatialMapping() not implemented.");
449 }

◆ EnableObjectDetection()

virtual sl::ERROR_CODE ZEDCamera::EnableObjectDetection ( const bool  bEnableBatching = false)
inlinevirtual

Enables object detection.

Parameters
bEnableBatching- Whether or not to enable batching.
Returns
sl::ERROR_CODE - The error code returned by the ZED SDK.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-25

Reimplemented in ZEDCam.

461 {
462 // Initialize instance variables.
463 (void) bEnableBatching;
464
465 // Submit logger message.
466 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::EnableObjectDetection(const bool bEnableBatching = false) not implemented.");
467
468 return sl::ERROR_CODE::FAILURE;
469 }

◆ DisableObjectDetection()

virtual void ZEDCamera::DisableObjectDetection ( )
inlinevirtual

Disables object detection.

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

Reimplemented in ZEDCam.

479 {
480 // Submit logger message.
481 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::DisableObjectDetection() not implemented.");
482 }

◆ GetUsingGPUMem()

virtual bool ZEDCamera::GetUsingGPUMem ( ) const
inlinevirtual

Accessor for the Using G P U Memory private member.

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-25

Reimplemented in SIMZEDCam, and ZEDCam.

497{ return false; }

◆ GetIsFusionMaster()

virtual bool ZEDCamera::GetIsFusionMaster ( ) const
inlinevirtual

Accessor for if this ZED is running a fusion instance.

Returns
true - This ZEDCam is a fusion master and is running an sl::Fusion instance.
false - This ZEDCam is not a fusion master and is not running a sl::Fusion instance.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-01-26
508{ return m_bCameraIsFusionMaster; }

◆ GetCameraModel()

virtual std::string ZEDCamera::GetCameraModel ( )
pure virtual

Accessor for the Camera Model private member.

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-25

Implemented in SIMZEDCam, and ZEDCam.

◆ GetCameraSerial()

virtual unsigned int ZEDCamera::GetCameraSerial ( )
inlinevirtual

Accessor for the Camera Serial private member.

Returns
unsigned int - 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
2024-12-25

Reimplemented in ZEDCam.

528{ return m_unCameraSerialNumber; };

◆ RequestPositionalPoseCopy()

virtual std::future< bool > ZEDCamera::RequestPositionalPoseCopy ( Pose stPose)
pure virtual

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

Parameters
stPose- A reference to the Pose to store the Pose in.
Returns
std::future<bool> - A future that should be waited on before the passed in Pose 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-25

Implemented in SIMZEDCam, and ZEDCam.

◆ RequestFusionGeoPoseCopy()

virtual std::future< bool > ZEDCamera::RequestFusionGeoPoseCopy ( sl::GeoPose &  slGeoPose)
pure virtual

Puts a 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-25

Implemented in SIMZEDCam, and ZEDCam.

◆ RequestFloorPlaneCopy()

virtual std::future< bool > ZEDCamera::RequestFloorPlaneCopy ( sl::Plane &  slFloorPlane)
inlinevirtual

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

Parameters
slFloorPlane- A reference to the sl::Plane to store the FloorPlane in.
Returns
std::future<bool> - A future that should be waited on before the passed in FloorPlane 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-25

Reimplemented in ZEDCam.

562 {
563 // Initialize instance variables.
564 (void) slFloorPlane;
565 std::promise<bool> pmPromise;
566
567 // Immediately set the promise to false.
568 pmPromise.set_value(false);
569
570 // Submit logger message.
571 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::RequestFloorPlaneCopy(sl::Plane& slFloorPlane) not implemented.");
572
573 return pmPromise.get_future();
574 }

◆ GetPositionalTrackingEnabled()

virtual bool ZEDCamera::GetPositionalTrackingEnabled ( )
pure virtual

Accessor for the Positional Tracking Enabled private member.

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

Implemented in SIMZEDCam, and ZEDCam.

◆ GetPositionalTrackingState()

virtual sl::PositionalTrackingStatus ZEDCamera::GetPositionalTrackingState ( )
inlinevirtual

Accessor for the Positional Tracking State private member.

Returns
sl::PositionalTrackingStatus - The positional tracking state.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-25

Reimplemented in ZEDCam.

596 {
597 // Initialize instance variable.
598 sl::PositionalTrackingStatus stStatus;
599
600 // Submit logger message.
601 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::GetPositionalTrackingState() not implemented.");
602
603 return stStatus;
604 }

◆ GetFusedPositionalTrackingState()

virtual sl::FusedPositionalTrackingStatus ZEDCamera::GetFusedPositionalTrackingState ( )
inlinevirtual

Accessor for the Fused Positional Tracking State private member.

Returns
sl::FusedPositionalTrackingStatus - The fused positional tracking state.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-25

Reimplemented in ZEDCam.

615 {
616 // Initialize instance variable.
617 sl::FusedPositionalTrackingStatus stStatus;
618
619 // Submit logger message.
620 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::GetFusedPositionalTrackingState() not implemented.");
621
622 return stStatus;
623 }

◆ GetSpatialMappingState()

virtual sl::SPATIAL_MAPPING_STATE ZEDCamera::GetSpatialMappingState ( )
inlinevirtual

Accessor for the Spatial Mapping State private member.

Returns
sl::SPATIAL_MAPPING_STATE - The spatial mapping state.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-25

Reimplemented in ZEDCam.

633{ return sl::SPATIAL_MAPPING_STATE::NOT_ENABLED; }

◆ ExtractSpatialMapAsync()

virtual sl::SPATIAL_MAPPING_STATE ZEDCamera::ExtractSpatialMapAsync ( std::future< sl::Mesh > &  fuMeshFuture)
inlinevirtual

Puts a Mesh pointer into a queue so a copy of a spatial mapping mesh from the camera can be written to it.

Parameters
fuMeshFuture- A future that should be waited on before the passed in Mesh is used.
Returns
sl::SPATIAL_MAPPING_STATE - The spatial mapping state.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-25

Reimplemented in ZEDCam.

645 {
646 // Initialize instance variables.
647 (void) fuMeshFuture;
648
649 // Submit logger message.
650 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::ExtractSpatialMapAsync(std::future<sl::Mesh>& fuMeshFuture) not implemented.");
651
652 return sl::SPATIAL_MAPPING_STATE::NOT_ENABLED;
653 }

◆ GetObjectDetectionEnabled()

virtual bool ZEDCamera::GetObjectDetectionEnabled ( )
inlinevirtual

Accessor for the Object Detection Enabled private member.

Returns
true - Object detection is enabled.
false - Object detection is not enabled.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-12-25

Reimplemented in ZEDCam.

664{ return false; }

◆ RequestObjectsCopy()

virtual std::future< bool > ZEDCamera::RequestObjectsCopy ( std::vector< sl::ObjectData > &  vObjectData)
inlinevirtual

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.

Parameters
vObjectData- A reference to the vector of sl::ObjectData to store the ObjectData in.
Returns
std::future<bool> - A future that should be waited on before the passed in ObjectData 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-25

Reimplemented in ZEDCam.

676 {
677 // Initialize instance variables.
678 (void) vObjectData;
679 std::promise<bool> pmPromise;
680
681 // Immediately set the promise to false.
682 pmPromise.set_value(false);
683
684 // Submit logger message.
685 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::RequestObjectsCopy(std::vector<sl::ObjectData>& vObjectData) not implemented.");
686
687 return pmPromise.get_future();
688 }

◆ RequestBatchedObjectsCopy()

virtual std::future< bool > ZEDCamera::RequestBatchedObjectsCopy ( std::vector< sl::ObjectsBatch > &  vBatchedObjectData)
inlinevirtual

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.

Parameters
vBatchedObjectData- A reference to the vector of sl::ObjectsBatch to store the ObjectsBatch in.
Returns
std::future<bool> - A future that should be waited on before the passed in ObjectsBatch 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-25

Reimplemented in ZEDCam.

700 {
701 // Initialize instance variables.
702 (void) vBatchedObjectData;
703 std::promise<bool> pmPromise;
704
705 // Immediately set the promise to false.
706 pmPromise.set_value(false);
707
708 // Submit logger message.
709 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::RequestBatchedObjectsCopy(std::vector<sl::ObjectsBatch>& vBatchedObjectData) not implemented.");
710
711 return pmPromise.get_future();
712 }

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