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

This class implements and interfaces with the most common ZEDSDK cameras and features. 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 <ZEDCam.h>

Inheritance diagram for ZEDCam:
Collaboration diagram for ZEDCam:

Public Member Functions

 ZEDCam (const int nPropResolutionX, const int nPropResolutionY, const int nPropFramesPerSecond, const double dPropHorizontalFOV, const double dPropVerticalFOV, const bool bEnableRecordingFlag, const float fMinSenseDistance=constants::ZED_DEFAULT_MINIMUM_DISTANCE, const float fMaxSenseDistance=constants::ZED_DEFAULT_MAXIMUM_DISTANCE, const bool bMemTypeGPU=false, const bool bUseHalfDepthPrecision=false, const bool bEnableFusionMaster=false, const int nNumFrameRetrievalThreads=10, const unsigned int unCameraSerialNumber=0)
 Construct a new Zed Cam:: Zed Cam object.
 
 ~ZEDCam ()
 Destroy the Zed Cam:: Zed Cam object.
 
std::future< bool > RequestFrameCopy (cv::Mat &cvFrame) override
 Requests a regular BGRA image from the LEFT eye of the zed camera. 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 > RequestFrameCopy (cv::cuda::GpuMat &cvGPUFrame) override
 Grabs a regular BGRA image from the LEFT eye of the zed camera and stores it in a GPU mat. 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) override
 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 > RequestDepthCopy (cv::cuda::GpuMat &cvGPUDepth, const bool bRetrieveMeasure=true) override
 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) override
 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 > RequestPointCloudCopy (cv::cuda::GpuMat &cvGPUPointCloud) override
 Grabs 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.
 
sl::ERROR_CODE ResetPositionalTracking () override
 Resets the cameras X,Y,Z translation and Roll,Pitch,Yaw orientation back to 0. THINK CAREFULLY! Do you actually want to reset this? It will also realign the coordinate system to whichever way the camera happens to be facing.
 
sl::ERROR_CODE TrackCustomBoxObjects (std::vector< ZedObjectData > &vCustomObjects) override
 A vector containing CustomBoxObjectData objects. These objects simply store information about your detected objects from an external object detection model. You will need to take your inference results and package them into a sl::CustomBoxObjectData so the the ZEDSDK can properly interpret your detections.
 
sl::ERROR_CODE RebootCamera () override
 Performs a hardware reset of the ZED2 or ZED2i camera.
 
sl::FUSION_ERROR_CODE SubscribeFusionToCameraUUID (sl::CameraIdentifier &slCameraUUID) override
 Give a UUID for another ZEDCam, subscribe that camera to this camera's Fusion instance. This will tell this camera's Fusion instance to start ingesting and fusing data from the other camera.
 
sl::CameraIdentifier PublishCameraToFusion () override
 Signal this camera to make its data available to the Fusion module and retrieve a UUID for this class's sl::Camera instance that can be used to subscribe an sl::Fusion instance to this camera later.
 
sl::FUSION_ERROR_CODE IngestGPSDataToFusion (geoops::GPSCoordinate stNewGPSLocation) override
 If this camera is the fusion instance master, this method can be used to ingest/process/fuse the current GNSS position of the camera with the ZEDSDK positional tracking. This allows the use of RequestGeoPose to get a high resolution and highly accurate GNSS/VIO camera pose.
 
sl::ERROR_CODE EnablePositionalTracking (const float fExpectedCameraHeightFromFloorTolerance=constants::ZED_DEFAULT_FLOOR_PLANE_ERROR) override
 Enable the positional tracking functionality of the camera.
 
void DisablePositionalTracking () override
 Disable to positional tracking functionality of the camera.
 
void SetPositionalPose (const double dX, const double dY, const double dZ, const double dXO, const double dYO, const double dZO) override
 Sets the pose of the positional tracking of the camera. XYZ will point in their respective directions according to ZED_COORD_SYSTEM defined in AutonomyConstants.h.
 
sl::ERROR_CODE EnableSpatialMapping () override
 Enabled the spatial mapping feature of the camera. Pose tracking will be enabled if it is not already.
 
void DisableSpatialMapping () override
 Disabled the spatial mapping feature of the camera.
 
sl::ERROR_CODE EnableObjectDetection (const bool bEnableBatching=false) override
 Enables the object detection and tracking feature of the camera.
 
void DisableObjectDetection () override
 Disables the object detection and tracking feature of the camera.
 
bool GetCameraIsOpen () override
 Accessor for the current status of the camera.
 
bool GetUsingGPUMem () const override
 Accessor for if this ZED is storing it's frames in GPU memory.
 
std::string GetCameraModel () override
 Accessor for the model enum from the ZEDSDK and represents the camera model as a string.
 
unsigned int GetCameraSerial () override
 Accessor for the camera's serial number.
 
std::future< bool > RequestPositionalPoseCopy (Pose &stPose) override
 Requests the current pose of the camera relative to it's start pose or the origin of the set pose. Puts a Pose pointer into a queue so a copy of a pose from the camera can be written to it. If positional tracking is not enabled, this method will return false and the ZEDCam::Pose may be uninitialized.
 
std::future< bool > RequestFusionGeoPoseCopy (sl::GeoPose &slGeoPose) override
 Requests the current geo pose of the camera. This method should be used to retrieve ONLY the GNSS data from the ZEDSDK's Fusion module. Puts a GeoPose pointer into a queue so a copy of a GeoPose from the camera can be written to it. If positional tracking or fusion is disabled for this camera, then this method will return false and the sl::GeoPose may be uninitialized.
 
std::future< bool > RequestFloorPlaneCopy (sl::Plane &slPlane) override
 Requests the current floor plane of the camera relative to it's current pose. Puts a Plane pointer into a queue so a copy of the floor plane from the camera can be written to it. If positional tracking is not enabled, this method will return false and the sl::Plane may be uninitialized.
 
bool GetPositionalTrackingEnabled () override
 Accessor for if the positional tracking functionality of the camera has been enabled and functioning.
 
sl::PositionalTrackingStatus GetPositionalTrackingState () override
 Accessor for the current positional tracking status of the camera.
 
sl::FusedPositionalTrackingStatus GetFusedPositionalTrackingState () override
 Accessor for the current positional tracking status of the fusion instance.
 
sl::SPATIAL_MAPPING_STATE GetSpatialMappingState () override
 Accessor for the current state of the camera's spatial mapping feature.
 
sl::SPATIAL_MAPPING_STATE ExtractSpatialMapAsync (std::future< sl::Mesh > &fuMeshFuture) override
 Retrieve the built spatial map from the camera. Spatial mapping must be enabled. This method takes in an std::future<sl::FusedPointCloud> to eventually store the map in. It returns a enum code representing the successful scheduling of building the map. Any code other than SPATIAL_MAPPING_STATE::OK means the future will never be filled.
 
bool GetObjectDetectionEnabled () override
 Accessor for if the cameras object detection and tracking feature is enabled.
 
std::future< bool > RequestObjectsCopy (std::vector< sl::ObjectData > &vObjectData) override
 Requests a current copy of the tracked objects from the camera. Puts a pointer to a vector containing sl::ObjectData into a queue so a copy of a frame from the camera can be written to it.
 
std::future< bool > RequestBatchedObjectsCopy (std::vector< sl::ObjectsBatch > &vBatchedObjectData) override
 If batching is enabled, this requests the normal objects and passes them to the the internal batching queue of the zed api. This performs short-term re-identification with deep learning and trajectories filtering. Batching must have been set to enabled when EnableObjectDetection() was called. Most of the time the vector will be empty and will be filled every ZED_OBJDETECTION_BATCH_LATENCY.
 
- 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 bool GetIsFusionMaster () const
 Accessor for if this ZED is running a fusion instance.
 
- 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 calls the grab() function of the ZEDSDK, which updates all frames (RGB, depth, cloud) and all other data such as positional and spatial mapping. 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 queue filled by the Request methods.
 

Private Attributes

sl::Camera m_slCamera
 
std::shared_mutex m_muCameraMutex
 
sl::InitParameters m_slCameraParams
 
sl::RuntimeParameters m_slRuntimeParams
 
sl::RecordingParameters m_slRecordingParams
 
sl::Fusion m_slFusionInstance
 
std::shared_mutex m_muFusionMutex
 
sl::InitFusionParameters m_slFusionParams
 
sl::MEASURE m_slDepthMeasureType
 
sl::PositionalTrackingParameters m_slPoseTrackingParams
 
sl::PositionalTrackingFusionParameters m_slFusionPoseTrackingParams
 
sl::Pose m_slCameraPose
 
sl::GeoPose m_slFusionGeoPose
 
sl::Plane m_slFloorPlane
 
sl::Transform m_slFloorTrackingTransform
 
sl::SpatialMappingParameters m_slSpatialMappingParams
 
sl::ObjectDetectionParameters m_slObjectDetectionParams
 
sl::BatchParameters m_slObjectDetectionBatchParams
 
sl::Objects m_slDetectedObjects
 
std::vector< sl::ObjectsBatch > m_slDetectedObjectsBatched
 
sl::MEM m_slMemoryType
 
sl::MODEL m_slCameraModel
 
float m_fExpectedCameraHeightFromFloorTolerance
 
double m_dPoseOffsetX
 
double m_dPoseOffsetY
 
double m_dPoseOffsetZ
 
double m_dPoseOffsetXO
 
double m_dPoseOffsetYO
 
double m_dPoseOffsetZO
 
geoops::GPSCoordinate m_stCurrentGPSBasedPosition
 
sl::Mat m_slFrame
 
sl::Mat m_slDepthImage
 
sl::Mat m_slDepthMeasure
 
sl::Mat m_slPointCloud
 
std::queue< containers::FrameFetchContainer< cv::cuda::GpuMat > > m_qGPUFrameCopySchedule
 
std::queue< containers::DataFetchContainer< std::vector< ZedObjectData > > > m_qCustomBoxIngestSchedule
 
std::queue< containers::DataFetchContainer< Pose > > m_qPoseCopySchedule
 
std::queue< containers::DataFetchContainer< sl::GeoPose > > m_qGeoPoseCopySchedule
 
std::queue< containers::DataFetchContainer< sl::Plane > > m_qFloorCopySchedule
 
std::queue< containers::DataFetchContainer< std::vector< sl::ObjectData > > > m_qObjectDataCopySchedule
 
std::queue< containers::DataFetchContainer< std::vector< sl::ObjectsBatch > > > m_qObjectBatchedDataCopySchedule
 
std::shared_mutex m_muCustomBoxIngestMutex
 
std::shared_mutex m_muPoseCopyMutex
 
std::shared_mutex m_muGeoPoseCopyMutex
 
std::shared_mutex m_muFloorCopyMutex
 
std::shared_mutex m_muObjectDataCopyMutex
 
std::shared_mutex m_muObjectBatchedDataCopyMutex
 
std::atomic< bool > m_bNormalFramesQueued
 
std::atomic< bool > m_bDepthFramesQueued
 
std::atomic< bool > m_bPointCloudsQueued
 
std::atomic< bool > m_bPosesQueued
 
std::atomic< bool > m_bGeoPosesQueued
 
std::atomic< bool > m_bFloorsQueued
 
std::atomic< bool > m_bObjectsQueued
 
std::atomic< bool > m_bBatchedObjectsQueued
 

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 most common ZEDSDK cameras and features. 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-21

Constructor & Destructor Documentation

◆ ZEDCam()

ZEDCam::ZEDCam ( const int  nPropResolutionX,
const int  nPropResolutionY,
const int  nPropFramesPerSecond,
const double  dPropHorizontalFOV,
const double  dPropVerticalFOV,
const bool  bEnableRecordingFlag,
const float  fMinSenseDistance = constants::ZED_DEFAULT_MINIMUM_DISTANCE,
const float  fMaxSenseDistance = constants::ZED_DEFAULT_MAXIMUM_DISTANCE,
const bool  bMemTypeGPU = false,
const bool  bUseHalfDepthPrecision = false,
const bool  bEnableFusionMaster = false,
const int  nNumFrameRetrievalThreads = 10,
const unsigned int  unCameraSerialNumber = 0 
)

Construct a new Zed Cam:: Zed Cam object.

Parameters
nPropResolutionX- X res of camera. Must be smaller than ZED_BASE_RESOLUTION.
nPropResolutionY- Y res of camera. Must be smaller than ZED_BASE_RESOLUTION.
nPropFramesPerSecond- FPS camera is running at.
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 to include in depth measures.
fMaxSenseDistance- The maximum distance to include in depth measures.
bMemTypeGPU- Whether or not to use the GPU memory for operations.
bUseHalfPrecision- Whether or not to use a float16 instead of float32 for depth measurements.
bEnableFusionMaster- Enables ZEDSDK Fusion integration for this camera. This camera will serve as the master instance for all fusion functions.
nNumFrameRetrievalThreads- The number of threads to use for copying frames/data to requests.
unCameraSerialNumber- The serial number of the camera to open.
Note
Do not set bEnableFusionMaster to true if you want to subscribe the camera to another camera! Only one camera should have Fusion enabled! To subscribe a camera to the camera running the master fusion instance, use the GetFusionInstance() and GetCameraSerial() functions. Refer to Fusion documentation for info on working with fusion functions: https://www.stereolabs.com/docs/api/classsl_1_1Fusion.html
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-08-26
52 :
53 ZEDCamera(nPropResolutionX,
54 nPropResolutionY,
55 nPropFramesPerSecond,
56 dPropHorizontalFOV,
57 dPropVerticalFOV,
58 bEnableRecordingFlag,
59 bMemTypeGPU,
60 bUseHalfDepthPrecision,
61 bEnableFusionMaster,
62 nNumFrameRetrievalThreads,
63 unCameraSerialNumber)
64{
65 // Assign member variables.
66 bMemTypeGPU ? m_slMemoryType = sl::MEM::GPU : m_slMemoryType = sl::MEM::CPU;
67 bUseHalfDepthPrecision ? m_slDepthMeasureType = sl::MEASURE::DEPTH_U16_MM : m_slDepthMeasureType = sl::MEASURE::DEPTH;
68 m_bCameraIsFusionMaster = bEnableFusionMaster;
69 m_dPoseOffsetX = 0.0;
70 m_dPoseOffsetY = 0.0;
71 m_dPoseOffsetZ = 0.0;
72 m_dPoseOffsetXO = 0.0;
73 m_dPoseOffsetYO = 0.0;
74 m_dPoseOffsetZO = 0.0;
75 // Initialize queued toggles.
76 m_bNormalFramesQueued = false;
77 m_bDepthFramesQueued = false;
78 m_bPointCloudsQueued = false;
79 m_bPosesQueued = false;
80 m_bGeoPosesQueued = false;
81 m_bFloorsQueued = false;
82 m_bObjectsQueued = false;
83 m_bBatchedObjectsQueued = false;
84
85 // Setup camera params.
86 m_slCameraParams.camera_resolution = constants::ZED_BASE_RESOLUTION;
87 m_slCameraParams.camera_fps = nPropFramesPerSecond;
88 m_slCameraParams.coordinate_units = constants::ZED_MEASURE_UNITS;
89 m_slCameraParams.coordinate_system = constants::ZED_COORD_SYSTEM;
90 m_slCameraParams.sdk_verbose = constants::ZED_SDK_VERBOSE;
91 m_slCameraParams.depth_mode = constants::ZED_DEPTH_MODE;
92 m_slCameraParams.depth_minimum_distance = fMinSenseDistance;
93 m_slCameraParams.depth_maximum_distance = fMaxSenseDistance;
94 m_slCameraParams.depth_stabilization = constants::ZED_DEPTH_STABILIZATION;
95 // Only set serial number if necessary.
96 if (unCameraSerialNumber != static_cast<unsigned int>(0))
97 {
98 m_slCameraParams.input.setFromSerialNumber(unCameraSerialNumber);
99 }
100
101 // Setup camera runtime params.
102 m_slRuntimeParams.enable_fill_mode = constants::ZED_SENSING_FILL;
103 // Setup SVO recording parameters.
104 m_slRecordingParams.compression_mode = constants::ZED_SVO_COMPRESSION;
105 m_slRecordingParams.bitrate = constants::ZED_SVO_BITRATE;
106
107 // Setup positional tracking parameters.
108 m_slPoseTrackingParams.mode = constants::ZED_POSETRACK_MODE;
109 m_slPoseTrackingParams.enable_area_memory = constants::ZED_POSETRACK_AREA_MEMORY;
110 m_slPoseTrackingParams.enable_pose_smoothing = constants::ZED_POSETRACK_POSE_SMOOTHING;
111 m_slPoseTrackingParams.set_floor_as_origin = constants::ZED_POSETRACK_FLOOR_IS_ORIGIN;
112 m_slPoseTrackingParams.enable_imu_fusion = constants::ZED_POSETRACK_ENABLE_IMU_FUSION;
113 m_slPoseTrackingParams.depth_min_range = constants::ZED_POSETRACK_USABLE_DEPTH_MIN;
114 m_slPoseTrackingParams.set_gravity_as_origin = constants::ZED_POSETRACK_USE_GRAVITY_ORIGIN;
115
116 // Setup spatial mapping parameters.
117 m_slSpatialMappingParams.map_type = constants::ZED_MAPPING_TYPE;
118 m_slSpatialMappingParams.resolution_meter = constants::ZED_MAPPING_RESOLUTION_METER;
119 m_slSpatialMappingParams.save_texture = true;
120 m_slSpatialMappingParams.use_chunk_only = constants::ZED_MAPPING_USE_CHUNK_ONLY;
121 m_slSpatialMappingParams.stability_counter = constants::ZED_MAPPING_STABILITY_COUNTER;
122 // Set or auto-set max depth range for mapping.
123 if (constants::ZED_MAPPING_RANGE_METER <= 0)
124 {
125 // Automatically guess the best mapping depth range.
126 m_slSpatialMappingParams.range_meter = m_slSpatialMappingParams.getRecommendedRange(constants::ZED_MAPPING_RESOLUTION_METER, m_slCamera);
127 }
128 else
129 {
130 // Manually set.
131 m_slSpatialMappingParams.range_meter = constants::ZED_MAPPING_RANGE_METER;
132 }
133
134 // Setup object detection/tracking parameters.
135 m_slObjectDetectionParams.detection_model = sl::OBJECT_DETECTION_MODEL::CUSTOM_BOX_OBJECTS;
136 m_slObjectDetectionParams.enable_tracking = constants::ZED_OBJDETECTION_TRACK_OBJ;
137 m_slObjectDetectionParams.enable_segmentation = constants::ZED_OBJDETECTION_SEGMENTATION;
138 m_slObjectDetectionParams.filtering_mode = constants::ZED_OBJDETECTION_FILTERING;
139 m_slObjectDetectionParams.prediction_timeout_s = constants::ZED_OBJDETECTION_TRACKING_PREDICTION_TIMEOUT;
140 // Setup object detection/tracking batch parameters.
141 m_slObjectDetectionBatchParams.enable = false;
142 m_slObjectDetectionBatchParams.id_retention_time = constants::ZED_OBJDETECTION_BATCH_RETENTION_TIME;
143 m_slObjectDetectionBatchParams.latency = constants::ZED_OBJDETECTION_BATCH_LATENCY;
144 m_slObjectDetectionParams.batch_parameters = m_slObjectDetectionBatchParams;
145
146 // Attempt to open camera.
147 sl::ERROR_CODE slReturnCode = m_slCamera.open(m_slCameraParams);
148 // Check if the camera was successfully opened.
149 if (m_slCamera.isOpened())
150 {
151 // Update camera serial number if camera was opened with autodetect.
152 m_unCameraSerialNumber = m_slCamera.getCameraInformation().serial_number;
153 // Update camera model.
154 m_slCameraModel = m_slCamera.getCameraInformation().camera_model;
155 // Check if the camera should record and output an SVO file.
156 if (m_bEnableRecordingFlag)
157 {
158 // Now that camera is opened get camera name and construct path.
159 std::string szSVOFilePath = constants::LOGGING_OUTPUT_PATH_ABSOLUTE + "/" + logging::g_szProgramStartTimeString + "/" + this->GetCameraModel() + "_" +
160 std::to_string(this->GetCameraSerial());
161 m_slRecordingParams.video_filename = szSVOFilePath.c_str();
162 // Enable recording.
163 sl::ERROR_CODE slReturnCode = m_slCamera.enableRecording(m_slRecordingParams);
164 // Check if recording was enabled successfully.
165 if (slReturnCode == sl::ERROR_CODE::SUCCESS)
166 {
167 // Submit logger message.
168 LOG_DEBUG(logging::g_qSharedLogger,
169 "Successfully enabled SVO recording for {} ZED stereo camera with serial number {}.",
170 this->GetCameraModel(),
171 m_unCameraSerialNumber);
172 }
173 else
174 {
175 // Submit logger message.
176 LOG_ERROR(logging::g_qSharedLogger,
177 "Failed to enable SVO recording for {} ZED stereo camera with serial number {}. sl::ERROR_CODE is {}",
178 this->GetCameraModel(),
179 m_unCameraSerialNumber,
180 sl::toString(slReturnCode).c_str());
181 }
182 }
183
184 // Submit logger message.
185 LOG_INFO(logging::g_qSharedLogger, "{} ZED stereo camera with serial number {} has been successfully opened.", this->GetCameraModel(), m_unCameraSerialNumber);
186 }
187 else
188 {
189 // Submit logger message.
190 LOG_ERROR(logging::g_qSharedLogger,
191 "Unable to open ZED stereo camera {} ({})! sl::ERROR_CODE is: {}",
192 sl::toString(m_slCameraModel).get(),
193 m_unCameraSerialNumber,
194 sl::toString(slReturnCode).get());
195 }
196
197 // Check if this camera should serve has the master Fusion instance.
198 if (bEnableFusionMaster)
199 {
200 // Setup Fusion params.
201 m_slFusionParams.coordinate_units = constants::FUSION_MEASUREMENT_UNITS;
202 m_slFusionParams.coordinate_system = constants::FUSION_COORD_SYSTEM;
203 m_slFusionParams.verbose = constants::FUSION_SDK_VERBOSE;
204 // Setup Fusion positional tracking parameters.
205 m_slFusionPoseTrackingParams.enable_GNSS_fusion = constants::FUSION_ENABLE_GNSS_FUSION;
206
207 // Initialize fusion instance for camera.
208 sl::FUSION_ERROR_CODE slReturnCode = m_slFusionInstance.init(m_slFusionParams);
209 // Check if fusion initialized properly.
210 if (slReturnCode == sl::FUSION_ERROR_CODE::SUCCESS)
211 {
212 // Enable odometry publishing for this ZED camera.
213 m_slCamera.startPublishing();
214 // Subscribe this camera to fusion instance.
215 slReturnCode = m_slFusionInstance.subscribe(sl::CameraIdentifier(m_unCameraSerialNumber));
216
217 // Check if this camera was successfully subscribed to the Fusion instance.
218 if (slReturnCode == sl::FUSION_ERROR_CODE::SUCCESS)
219 {
220 // Submit logger message.
221 LOG_DEBUG(logging::g_qSharedLogger, "Initialized FUSION instance for ZED camera {} ({})!", sl::toString(m_slCameraModel).get(), m_unCameraSerialNumber);
222 }
223 else
224 {
225 // Submit logger message.
226 LOG_DEBUG(logging::g_qSharedLogger,
227 "Unable to subscribe to internal FUSION instance for camera {} ({})! sl::FUSION_ERROR_CODE is: {}",
228 sl::toString(m_slCameraModel).get(),
229 m_unCameraSerialNumber,
230 sl::toString(slReturnCode).get());
231 }
232 }
233 else
234 {
235 // Submit logger message.
236 LOG_ERROR(logging::g_qSharedLogger,
237 "Unable to initialize FUSION instance for camera {} ({})! sl::FUSION_ERROR_CODE is: {}",
238 sl::toString(m_slCameraModel).get(),
239 m_unCameraSerialNumber,
240 sl::toString(slReturnCode).get());
241 }
242 }
243
244 // Set max FPS of the ThreadedContinuousCode method.
245 this->SetMainThreadIPSLimit(nPropFramesPerSecond);
246}
void SetMainThreadIPSLimit(int nMaxIterationsPerSecond=0)
Mutator for the Main Thread Max I P S private member.
Definition AutonomyThread.hpp:467
unsigned int GetCameraSerial() override
Accessor for the camera's serial number.
Definition ZEDCam.cpp:1886
std::string GetCameraModel() override
Accessor for the model enum from the ZEDSDK and represents the camera model as a string.
Definition ZEDCam.cpp:1857
This class serves as a middle inheritor between the Camera interface and the ZEDCam class....
Definition ZEDCamera.hpp:33
__host__ cudaTextureObject_t get() const noexcept
Here is the call graph for this function:

◆ ~ZEDCam()

ZEDCam::~ZEDCam ( )

Destroy the Zed Cam:: Zed Cam object.

Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-08-26
256{
257 // Stop threaded code.
258 this->RequestStop();
259 this->Join();
260
261 // Check if fusion master instance has been started for this camera.
262 if (m_bCameraIsFusionMaster)
263 {
264 // Close Fusion instance.
265 m_slFusionInstance.close();
266 }
267
268 // Close the ZEDCam.
269 m_slCamera.close();
270
271 // Submit logger message.
272 LOG_INFO(logging::g_qSharedLogger, "ZED stereo camera with serial number {} has been successfully closed.", m_unCameraSerialNumber);
273}
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() [1/2]

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

Requests a regular BGRA image from the LEFT eye of the zed camera. 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 copy the normal 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-09-09

Implements ZEDCamera.

954{
955 // Assemble the FrameFetchContainer.
956 containers::FrameFetchContainer<cv::Mat> stContainer(cvFrame, PIXEL_FORMATS::eBGRA);
957
958 // Acquire lock on frame copy queue.
959 std::unique_lock<std::shared_mutex> lkSchedulers(m_muPoolScheduleMutex);
960 // Append frame fetch container to the schedule queue.
961 m_qFrameCopySchedule.push(stContainer);
962 // Release lock on the frame schedule queue.
963 lkSchedulers.unlock();
964
965 // Check if frame queue toggle has already been set.
966 if (!m_bNormalFramesQueued.load(ATOMIC_MEMORY_ORDER_METHOD))
967 {
968 // Signify that the frame queue is not empty.
969 m_bNormalFramesQueued.store(true, ATOMIC_MEMORY_ORDER_METHOD);
970 }
971
972 // Return the future from the promise stored in the container.
973 return stContainer.pCopiedFrameStatus->get_future();
974}
This struct is used to carry references to camera frames for scheduling and copying....
Definition FetchContainers.hpp:86

◆ RequestFrameCopy() [2/2]

std::future< bool > ZEDCam::RequestFrameCopy ( cv::cuda::GpuMat cvGPUFrame)
overridevirtual

Grabs a regular BGRA image from the LEFT eye of the zed camera and stores it in a GPU mat. 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
cvGPUFrame- A reference to the cv::Mat to copy the normal 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-09-09

Reimplemented from ZEDCamera.

989{
990 // Assemble the FrameFetchContainer.
991 containers::FrameFetchContainer<cv::cuda::GpuMat> stContainer(cvGPUFrame, PIXEL_FORMATS::eBGRA);
992
993 // Acquire lock on frame copy queue.
994 std::unique_lock<std::shared_mutex> lkSchedulers(m_muPoolScheduleMutex);
995 // Append frame fetch container to the schedule queue.
996 m_qGPUFrameCopySchedule.push(stContainer);
997 // Release lock on the frame schedule queue.
998 lkSchedulers.unlock();
999
1000 // Check if frame queue toggle has already been set.
1001 if (!m_bNormalFramesQueued.load(ATOMIC_MEMORY_ORDER_METHOD))
1002 {
1003 // Signify that the frame queue is not empty.
1004 m_bNormalFramesQueued.store(true, ATOMIC_MEMORY_ORDER_METHOD);
1005 }
1006
1007 // Return the future from the promise stored in the container.
1008 return stContainer.pCopiedFrameStatus->get_future();
1009}

◆ RequestDepthCopy() [1/2]

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

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.

1027{
1028 // Create instance variables.
1029 PIXEL_FORMATS eFrameType;
1030
1031 // Check if the container should be set to retrieve an image or a measure.
1032 bRetrieveMeasure ? eFrameType = PIXEL_FORMATS::eDepthMeasure : eFrameType = PIXEL_FORMATS::eDepthImage;
1033 // Assemble container.
1034 containers::FrameFetchContainer<cv::Mat> stContainer(cvDepth, eFrameType);
1035
1036 // Acquire lock on frame copy queue.
1037 std::unique_lock<std::shared_mutex> lkSchedulers(m_muPoolScheduleMutex);
1038 // Append frame fetch container to the schedule queue.
1039 m_qFrameCopySchedule.push(stContainer);
1040 // Release lock on the frame schedule queue.
1041 lkSchedulers.unlock();
1042
1043 // Check if frame queue toggle has already been set.
1044 if (!m_bDepthFramesQueued.load(ATOMIC_MEMORY_ORDER_METHOD))
1045 {
1046 // Signify that the frame queue is not empty.
1047 m_bDepthFramesQueued.store(true, ATOMIC_MEMORY_ORDER_METHOD);
1048 }
1049
1050 // Return the future from the promise stored in the container.
1051 return stContainer.pCopiedFrameStatus->get_future();
1052}

◆ RequestDepthCopy() [2/2]

std::future< bool > ZEDCam::RequestDepthCopy ( cv::cuda::GpuMat cvGPUDepth,
const bool  bRetrieveMeasure = true 
)
overridevirtual

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

Reimplemented from ZEDCamera.

1070{
1071 // Create instance variables.
1072 PIXEL_FORMATS eFrameType;
1073
1074 // Check if the container should be set to retrieve an image or a measure.
1075 bRetrieveMeasure ? eFrameType = PIXEL_FORMATS::eDepthMeasure : eFrameType = PIXEL_FORMATS::eDepthImage;
1076 // Assemble container.
1077 containers::FrameFetchContainer<cv::cuda::GpuMat> stContainer(cvGPUDepth, eFrameType);
1078
1079 // Acquire lock on frame copy queue.
1080 std::unique_lock<std::shared_mutex> lkSchedulers(m_muPoolScheduleMutex);
1081 // Append frame fetch container to the schedule queue.
1082 m_qGPUFrameCopySchedule.push(stContainer);
1083 // Release lock on the frame schedule queue.
1084 lkSchedulers.unlock();
1085
1086 // Check if frame queue toggle has already been set.
1087 if (!m_bDepthFramesQueued.load(ATOMIC_MEMORY_ORDER_METHOD))
1088 {
1089 // Signify that the frame queue is not empty.
1090 m_bDepthFramesQueued.store(true, ATOMIC_MEMORY_ORDER_METHOD);
1091 }
1092
1093 // Return the future from the promise stored in the container.
1094 return stContainer.pCopiedFrameStatus->get_future();
1095}

◆ RequestPointCloudCopy() [1/2]

std::future< bool > ZEDCam::RequestPointCloudCopy ( cv::Mat cvPointCloud)
overridevirtual

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.

A 4th value in the 3rd dimension exists as a float32 storing the BGRA values. Each color value is 8-bits and is in this order: 00000000 00000000 00000000 00000000 = 32 bits (float32) B G R A

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.

1118{
1119 // Assemble the FrameFetchContainer.
1120 containers::FrameFetchContainer<cv::Mat> stContainer(cvPointCloud, PIXEL_FORMATS::eXYZBGRA);
1121
1122 // Acquire lock on frame copy queue.
1123 std::unique_lock<std::shared_mutex> lkSchedulers(m_muPoolScheduleMutex);
1124 // Append frame fetch container to the schedule queue.
1125 m_qFrameCopySchedule.push(stContainer);
1126 // Release lock on the frame schedule queue.
1127 lkSchedulers.unlock();
1128
1129 // Check if point cloud queue toggle has already been set.
1130 if (!m_bPointCloudsQueued.load(ATOMIC_MEMORY_ORDER_METHOD))
1131 {
1132 // Signify that the point cloud queue is not empty.
1133 m_bPointCloudsQueued.store(true, ATOMIC_MEMORY_ORDER_METHOD);
1134 }
1135
1136 // Return the future from the promise stored in the container.
1137 return stContainer.pCopiedFrameStatus->get_future();
1138}

◆ RequestPointCloudCopy() [2/2]

std::future< bool > ZEDCam::RequestPointCloudCopy ( cv::cuda::GpuMat cvGPUPointCloud)
overridevirtual

Grabs 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.

A 4th value in the 3rd dimension exists as a float32 storing the BGRA values. Each color value is 8-bits and is in this order: 00000000 00000000 00000000 00000000 = 32 bits (float32) B G R A

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

Parameters
cvGPUPointCloud- 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

Reimplemented from ZEDCamera.

1161{
1162 // Assemble the FrameFetchContainer.
1163 containers::FrameFetchContainer<cv::cuda::GpuMat> stContainer(cvGPUPointCloud, PIXEL_FORMATS::eXYZBGRA);
1164
1165 // Acquire lock on frame copy queue.
1166 std::unique_lock<std::shared_mutex> lkSchedulers(m_muPoolScheduleMutex);
1167 // Append frame fetch container to the schedule queue.
1168 m_qGPUFrameCopySchedule.push(stContainer);
1169 // Release lock on the frame schedule queue.
1170 lkSchedulers.unlock();
1171
1172 // Check if point cloud queue toggle has already been set.
1173 if (!m_bPointCloudsQueued.load(ATOMIC_MEMORY_ORDER_METHOD))
1174 {
1175 // Signify that the point cloud queue is not empty.
1176 m_bPointCloudsQueued.store(true, ATOMIC_MEMORY_ORDER_METHOD);
1177 }
1178
1179 // Return the future from the promise stored in the container.
1180 return stContainer.pCopiedFrameStatus->get_future();
1181}

◆ ResetPositionalTracking()

sl::ERROR_CODE ZEDCam::ResetPositionalTracking ( )
overridevirtual

Resets the cameras X,Y,Z translation and Roll,Pitch,Yaw orientation back to 0. THINK CAREFULLY! Do you actually want to reset this? It will also realign the coordinate system to whichever way the camera happens to be facing.

Returns
sl::ERROR_CODE - Status of the positional tracking reset.
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.

1194{
1195 // Create new translation to set position back to user given values.
1196 sl::Translation slZeroTranslation(0, 0, 0);
1197 // Update offset member variables.
1198 m_dPoseOffsetX = 0.0;
1199 m_dPoseOffsetY = 0.0;
1200 m_dPoseOffsetZ = 0.0;
1201 // This will reset position and coordinate frame.
1202 sl::Rotation slZeroRotation;
1203 slZeroRotation.setEulerAngles(sl::float3(0.0, 0.0, 0.0), false);
1204
1205 // Store new translation and rotation in a transform object.
1206 sl::Transform slZeroTransform(slZeroRotation, slZeroTranslation);
1207
1208 // Submit logger message.
1209 LOG_NOTICE(logging::g_qSharedLogger, "Resetting positional tracking for camera {} ({})!", sl::toString(m_slCameraModel).get(), m_unCameraSerialNumber);
1210
1211 // Acquire write lock.
1212 std::unique_lock<std::shared_mutex> lkWriteCameraLock(m_muCameraMutex);
1213 // Reset the positional tracking location of the camera.
1214 return m_slCamera.resetPositionalTracking(slZeroTransform);
1215}
Here is the call graph for this function:

◆ TrackCustomBoxObjects()

sl::ERROR_CODE ZEDCam::TrackCustomBoxObjects ( std::vector< ZedObjectData > &  vCustomObjects)
overridevirtual

A vector containing CustomBoxObjectData objects. These objects simply store information about your detected objects from an external object detection model. You will need to take your inference results and package them into a sl::CustomBoxObjectData so the the ZEDSDK can properly interpret your detections.

Giving the bounding boxes of your detected objects to the ZEDSDK will enable positional tracking and velocity estimation for each object. Even when not in view. The IDs of objects will also become persistent.

Parameters
vCustomObjects- A vector of sl::CustomBoxObjectData objects.
Returns
sl::ERROR_CODE - The return status of ingestion.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-08-26

Reimplemented from ZEDCamera.

1234{
1235 // Create instance variables.
1236 std::vector<sl::CustomBoxObjectData> vCustomBoxData;
1237
1238 // Repack detection data into sl specific object.
1239 for (ZedObjectData stObjectData : vCustomObjects)
1240 {
1241 // Create new sl CustomBoxObjectData struct.
1242 sl::CustomBoxObjectData slCustomBox;
1243 std::vector<sl::uint2> vCorners;
1244
1245 // Assign simple attributes.
1246 slCustomBox.unique_object_id = sl::String(stObjectData.GetObjectUUID().c_str());
1247 slCustomBox.label = stObjectData.nClassNumber;
1248 slCustomBox.probability = stObjectData.fConfidence;
1249 slCustomBox.is_grounded = stObjectData.bObjectRemainsOnFloorPlane;
1250 // Repackage object corner data.
1251 vCorners.emplace_back(sl::uint2(stObjectData.CornerTL.nX, stObjectData.CornerTL.nY));
1252 vCorners.emplace_back(sl::uint2(stObjectData.CornerTR.nX, stObjectData.CornerTR.nY));
1253 vCorners.emplace_back(sl::uint2(stObjectData.CornerBL.nX, stObjectData.CornerBL.nY));
1254 vCorners.emplace_back(sl::uint2(stObjectData.CornerBR.nX, stObjectData.CornerBR.nY));
1255 slCustomBox.bounding_box_2d = vCorners;
1256
1257 // Append repackaged object to vector.
1258 vCustomBoxData.emplace_back(slCustomBox);
1259 }
1260
1261 // Acquire write lock.
1262 std::unique_lock<std::shared_mutex> lkWriteCameraLock(m_muCameraMutex);
1263 // Give the custom box data to the zed api.
1264 sl::ERROR_CODE slReturnCode = m_slCamera.ingestCustomBoxObjects(vCustomBoxData);
1265 // Release lock.
1266 lkWriteCameraLock.unlock();
1267
1268 // Check if successful.
1269 if (slReturnCode == sl::ERROR_CODE::SUCCESS)
1270 {
1271 // Submit logger message.
1272 LOG_WARNING(logging::g_qSharedLogger,
1273 "Failed to ingest new objects for camera {} ({})! sl::ERROR_CODE is: {}",
1274 sl::toString(m_slCameraModel).get(),
1275 m_unCameraSerialNumber,
1276 sl::toString(slReturnCode).get());
1277 }
1278
1279 // Return error code.
1280 return slReturnCode;
1281}
Here is the call graph for this function:

◆ RebootCamera()

sl::ERROR_CODE ZEDCam::RebootCamera ( )
overridevirtual

Performs a hardware reset of the ZED2 or ZED2i camera.

Returns
sl::ERROR_CODE - Whether or not the camera reboot was successful.
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.

1292{
1293 // Acquire write lock.
1294 std::unique_lock<std::shared_mutex> lkCameraLock(m_muCameraMutex);
1295 // Reboot this camera and return the status code.
1296 return sl::Camera::reboot(m_unCameraSerialNumber);
1297}

◆ SubscribeFusionToCameraUUID()

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

Give a UUID for another ZEDCam, subscribe that camera to this camera's Fusion instance. This will tell this camera's Fusion instance to start ingesting and fusing data from the other camera.

Parameters
slCameraUUID- The Camera unique identifier given by the other camera's PublishCameraToFusion() method.
Returns
sl::FUSION_ERROR_CODE - Whether or not the camera and fusion module has been successfully subscribed.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-01-26

Implements ZEDCamera.

1310{
1311 // Create instance variables.
1312 sl::FUSION_ERROR_CODE slReturnCode = sl::FUSION_ERROR_CODE::MODULE_NOT_ENABLED;
1313
1314 // Check if this camera is a fusion master.
1315 if (m_bCameraIsFusionMaster)
1316 {
1317 // Acquire write lock.
1318 std::unique_lock<std::shared_mutex> lkFusionLock(m_muFusionMutex);
1319 // Subscribe this camera to fusion instance.
1320 slReturnCode = m_slFusionInstance.subscribe(slCameraUUID);
1321 // Release lock.
1322 lkFusionLock.unlock();
1323 }
1324
1325 // Check if this camera was successfully subscribed to the Fusion instance.
1326 if (slReturnCode == sl::FUSION_ERROR_CODE::SUCCESS)
1327 {
1328 // Submit logger message.
1329 LOG_DEBUG(logging::g_qSharedLogger,
1330 "Subscribed stereo camera with serial number {} to Fusion instance ran by stereo camera {} ({})!",
1331 slCameraUUID.sn,
1332 sl::toString(m_slCameraModel).get(),
1333 m_unCameraSerialNumber);
1334 }
1335 else
1336 {
1337 // Submit logger message.
1338 LOG_DEBUG(logging::g_qSharedLogger,
1339 "Unable to subscribe camera with serial number {} to FUSION instance for camera {} ({})! sl::FUSION_ERROR_CODE is: {}",
1340 slCameraUUID.sn,
1341 sl::toString(m_slCameraModel).get(),
1342 m_unCameraSerialNumber,
1343 sl::toString(slReturnCode).get());
1344 }
1345
1346 // Return the sl::FUSION_ERROR_CODE status.
1347 return slReturnCode;
1348}

◆ PublishCameraToFusion()

sl::CameraIdentifier ZEDCam::PublishCameraToFusion ( )
overridevirtual

Signal this camera to make its data available to the Fusion module and retrieve a UUID for this class's sl::Camera instance that can be used to subscribe an sl::Fusion instance to this camera later.

Returns
sl::CameraIdentifier - A globally unique identifier generated from this camera's serial number.
Note
Just calling this method does not send data to the ZEDSDK's fusion module. It just enables the capability. The camera acting as the fusion master instance must be subscribed to this camera using the SubscribeFusionToCameraUUID() method and the returned UUID.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-01-26

Implements ZEDCamera.

1365{
1366 // Acquire write lock.
1367 std::unique_lock<std::shared_mutex> lkWriteCameraLock(m_muCameraMutex);
1368 // Make this cameras data available to the Fusion module if it is later subscribed.
1369 m_slCamera.startPublishing();
1370 // Release lock.
1371 lkWriteCameraLock.unlock();
1372
1373 // Return a UUID for this camera. This is used by the camera running the master fusion instance to subscribe to the data being published.
1374 return sl::CameraIdentifier(m_unCameraSerialNumber);
1375}

◆ IngestGPSDataToFusion()

sl::FUSION_ERROR_CODE ZEDCam::IngestGPSDataToFusion ( geoops::GPSCoordinate  stNewGPSLocation)
overridevirtual

If this camera is the fusion instance master, this method can be used to ingest/process/fuse the current GNSS position of the camera with the ZEDSDK positional tracking. This allows the use of RequestGeoPose to get a high resolution and highly accurate GNSS/VIO camera pose.

Parameters
stNewGPSLocation- The current GPS location, this must be up-to-date or the realtime position of the camera in the GPS space.
Returns
sl::FUSION_ERROR_CODE - Return status from the ZEDSDK Fusion module.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-04-15

Reimplemented from ZEDCamera.

1389{
1390 // Create instance variables.
1391 sl::FUSION_ERROR_CODE slReturnCode = sl::FUSION_ERROR_CODE::FAILURE;
1392
1393 // Check if this camera is the fusion master.
1394 if (m_bCameraIsFusionMaster)
1395 {
1396 // Acquire read lock.
1397 std::shared_lock<std::shared_mutex> lkCameraLock(m_muCameraMutex);
1398 // Check if fusion positional tracking is enabled.
1399 if (constants::FUSION_ENABLE_GNSS_FUSION && m_slCamera.isPositionalTrackingEnabled())
1400 {
1401 // Release lock.
1402 lkCameraLock.unlock();
1403
1404 // Check if the GPS data from the NavBoard is recent.
1405 if (stNewGPSLocation.dLatitude != m_stCurrentGPSBasedPosition.dLatitude && stNewGPSLocation.dLongitude != m_stCurrentGPSBasedPosition.dLongitude &&
1406 stNewGPSLocation.d2DAccuracy != m_stCurrentGPSBasedPosition.d2DAccuracy && stNewGPSLocation.d3DAccuracy != m_stCurrentGPSBasedPosition.d3DAccuracy)
1407 {
1408 // Repack gps data int sl::GNSSData object.
1409 sl::GNSSData slGNSSData = sl::GNSSData();
1410 slGNSSData.setCoordinates(stNewGPSLocation.dLatitude, stNewGPSLocation.dLongitude, stNewGPSLocation.dAltitude, false);
1411 // Position covariance matrix expects millimeters.
1412 double dHorizontalAccuracy = stNewGPSLocation.d2DAccuracy * 1000;
1413 double dVerticalAccuracy = stNewGPSLocation.d3DAccuracy * 1000;
1414 // Calculate the covariance matrix from the 2D and 3D accuracies.
1415 slGNSSData.position_covariance = {dHorizontalAccuracy * dHorizontalAccuracy,
1416 0.0,
1417 0.0,
1418 0.0,
1419 dHorizontalAccuracy * dHorizontalAccuracy,
1420 0.0,
1421 0.0,
1422 0.0,
1423 dVerticalAccuracy * dVerticalAccuracy};
1424
1425 // Set GNSS timestamp from input GPSCoordinate data. sl::GNSSData expects time since epoch.
1426 slGNSSData.ts = sl::Timestamp(std::chrono::time_point_cast<std::chrono::nanoseconds>(stNewGPSLocation.tmTimestamp).time_since_epoch().count());
1427
1428 // Get the GNSS fix type status from the given GPS coordinate.
1429 switch (stNewGPSLocation.eCoordinateAccuracyFixType)
1430 {
1431 case geoops::PositionFixType::eNoFix:
1432 {
1433 slGNSSData.gnss_status = sl::GNSS_STATUS::SINGLE;
1434 slGNSSData.gnss_mode = sl::GNSS_MODE::NO_FIX;
1435 break;
1436 }
1437 case geoops::PositionFixType::eDeadReckoning:
1438 {
1439 slGNSSData.gnss_status = sl::GNSS_STATUS::PPS;
1440 slGNSSData.gnss_mode = sl::GNSS_MODE::NO_FIX;
1441 break;
1442 }
1443 case geoops::PositionFixType::eFix2D:
1444 {
1445 slGNSSData.gnss_status = sl::GNSS_STATUS::PPS;
1446 slGNSSData.gnss_mode = sl::GNSS_MODE::FIX_2D;
1447 break;
1448 }
1449 case geoops::PositionFixType::eFix3D:
1450 {
1451 slGNSSData.gnss_status = sl::GNSS_STATUS::RTK_FIX;
1452 slGNSSData.gnss_mode = sl::GNSS_MODE::FIX_3D;
1453 break;
1454 }
1455 case geoops::PositionFixType::eGNSSDeadReckoningCombined:
1456 {
1457 slGNSSData.gnss_status = sl::GNSS_STATUS::RTK_FIX;
1458 slGNSSData.gnss_mode = sl::GNSS_MODE::FIX_3D;
1459 break;
1460 }
1461 case geoops::PositionFixType::eTimeOnly:
1462 {
1463 slGNSSData.gnss_status = sl::GNSS_STATUS::RTK_FIX;
1464 slGNSSData.gnss_mode = sl::GNSS_MODE::FIX_3D;
1465 break;
1466 }
1467 default:
1468 {
1469 slGNSSData.gnss_status = sl::GNSS_STATUS::RTK_FIX;
1470 slGNSSData.gnss_mode = sl::GNSS_MODE::FIX_3D;
1471 break;
1472 }
1473 }
1474 // Check if fix is based off of differential GPS calculations.
1475 if (stNewGPSLocation.bIsDifferential)
1476 {
1477 slGNSSData.gnss_status = sl::GNSS_STATUS::DGNSS;
1478 }
1479
1480 // Acquire write lock.
1481 std::unique_lock<std::shared_mutex> lkFusionLock(m_muFusionMutex);
1482 // Publish GNSS data to fusion from the NavBoard.
1483 slReturnCode = m_slFusionInstance.ingestGNSSData(slGNSSData);
1484 // Release lock.
1485 lkFusionLock.unlock();
1486 // Check if the GNSS data was successfully ingested by the Fusion instance.
1487 if (slReturnCode != sl::FUSION_ERROR_CODE::SUCCESS)
1488 {
1489 // Covariance error.
1490 if (slReturnCode == sl::FUSION_ERROR_CODE::GNSS_DATA_COVARIANCE_MUST_VARY || slReturnCode == sl::FUSION_ERROR_CODE::INVALID_COVARIANCE)
1491 {
1492 // Submit logger message.
1493 LOG_WARNING(logging::g_qSharedLogger,
1494 "Unable to ingest fusion GNSS data for camera {} ({})! sl::Fusion positional tracking may be inaccurate! sl::FUSION_ERROR_CODE "
1495 "is: {}({}). Current accuracy data is 2D: {}, 3D {}.",
1496 sl::toString(m_slCameraModel).get(),
1497 m_unCameraSerialNumber,
1498 sl::toString(slReturnCode).get(),
1499 static_cast<int>(slReturnCode),
1500 stNewGPSLocation.d2DAccuracy,
1501 stNewGPSLocation.d3DAccuracy);
1502 }
1503 else if (slReturnCode != sl::FUSION_ERROR_CODE::NO_NEW_DATA_AVAILABLE)
1504 {
1505 // Submit logger message.
1506 LOG_WARNING(logging::g_qSharedLogger,
1507 "Unable to ingest fusion GNSS data for camera {} ({})! sl::Fusion positional tracking may be inaccurate! sl::FUSION_ERROR_CODE "
1508 "is: {}({})",
1509 sl::toString(m_slCameraModel).get(),
1510 m_unCameraSerialNumber,
1511 sl::toString(slReturnCode).get(),
1512 static_cast<int>(slReturnCode));
1513 }
1514 }
1515 else
1516 {
1517 // Acquire write lock.
1518 std::shared_lock<std::shared_mutex> lkFusionLock(m_muFusionMutex);
1519 // Get the current status of the fusion positional tracking.
1520 sl::FusedPositionalTrackingStatus slFusionPoseTrackStatus = m_slFusionInstance.getFusedPositionalTrackingStatus();
1521 // Release lock.
1522 lkFusionLock.unlock();
1523 // Submit logger message. DEBUG log the current fused position tracking state.
1524 LOG_DEBUG(logging::g_qSharedLogger,
1525 "PoseTrack Fusion Status: {}, GNSS Fusion Status: {}, VIO SpatialMemory Status: {}",
1526 sl::toString(slFusionPoseTrackStatus.tracking_fusion_status).get(),
1527 sl::toString(slFusionPoseTrackStatus.gnss_fusion_status).get(),
1528 sl::toString(slFusionPoseTrackStatus.spatial_memory_status).get());
1529 }
1530
1531 // Update current GPS position.
1532 m_stCurrentGPSBasedPosition = stNewGPSLocation;
1533 }
1534 }
1535 else
1536 {
1537 // Release lock.
1538 lkCameraLock.unlock();
1539 // Submit logger message.
1540 LOG_ERROR(logging::g_qSharedLogger,
1541 "Cannot ingest GNSS data because camera {} ({}) does not have positional tracking enabled or constants::FUSION_ENABLE_GNSS_FUSION is false!",
1542 sl::toString(m_slCameraModel).get(),
1543 m_unCameraSerialNumber);
1544 }
1545 }
1546 else
1547 {
1548 // Submit logger message.
1549 LOG_WARNING(logging::g_qSharedLogger,
1550 "Cannot ingest GNSS data because camera {} ({}) is not an sl::Fusion master!",
1551 sl::toString(m_slCameraModel).get(),
1552 m_unCameraSerialNumber);
1553 }
1554
1555 return slReturnCode;
1556}
Here is the call graph for this function:

◆ EnablePositionalTracking()

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

Enable the positional tracking functionality of the camera.

Parameters
fExpectedCameraHeightFromFloorTolerance- The expected height of the camera from the floor. This aids with floor plane detection.
Returns
sl::ERROR_CODE - Whether or not positional tracking was successfully enabled.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-10-22

Implements ZEDCamera.

1569{
1570 // Assign member variable.
1571 m_fExpectedCameraHeightFromFloorTolerance = fExpectedCameraHeightFromFloorTolerance;
1572
1573 // Acquire write lock.
1574 std::unique_lock<std::shared_mutex> lkCameraLock(m_muCameraMutex);
1575 // Enable pose tracking and store return code.
1576 sl::ERROR_CODE slReturnCode = m_slCamera.enablePositionalTracking(m_slPoseTrackingParams);
1577 // Release lock.
1578 lkCameraLock.unlock();
1579
1580 // Check if positional tracking was enabled properly.
1581 if (slReturnCode != sl::ERROR_CODE::SUCCESS)
1582 {
1583 // Submit logger message.
1584 LOG_ERROR(logging::g_qSharedLogger,
1585 "Failed to enable positional tracking for camera {} ({})! sl::ERROR_CODE is: {}",
1586 sl::toString(m_slCameraModel).get(),
1587 m_unCameraSerialNumber,
1588 sl::toString(slReturnCode).get());
1589 }
1590 // Check if fusion positional tracking should be enabled for this camera.
1591 else if (m_bCameraIsFusionMaster)
1592 {
1593 // Acquire write lock.
1594 std::unique_lock<std::shared_mutex> lkFusionLock(m_muFusionMutex);
1595 // Enable fusion positional tracking.
1596 sl::FUSION_ERROR_CODE slFusionReturnCode = m_slFusionInstance.enablePositionalTracking(m_slFusionPoseTrackingParams);
1597 // Release lock.
1598 lkFusionLock.unlock();
1599
1600 // Check if the fusion positional tracking was enabled successfully.
1601 if (slFusionReturnCode != sl::FUSION_ERROR_CODE::SUCCESS)
1602 {
1603 // Submit logger message.
1604 LOG_ERROR(logging::g_qSharedLogger,
1605 "Failed to enable fusion positional tracking for camera {} ({})! sl::FUSION_ERROR_CODE is: {}",
1606 sl::toString(m_slCameraModel).get(),
1607 m_unCameraSerialNumber,
1608 sl::toString(slFusionReturnCode).get());
1609 }
1610 }
1611
1612 // Return error code.
1613 return slReturnCode;
1614}
Here is the call graph for this function:
Here is the caller graph for this function:

◆ DisablePositionalTracking()

void ZEDCam::DisablePositionalTracking ( )
overridevirtual

Disable to positional tracking functionality 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-08-26

Implements ZEDCamera.

1624{
1625 // Check if fusion positional tracking should be enabled for this camera.
1626 if (m_bCameraIsFusionMaster)
1627 {
1628 // Acquire write lock.
1629 std::unique_lock<std::shared_mutex> lkFusionLock(m_muFusionMutex);
1630 // Enable fusion positional tracking.
1631 m_slFusionInstance.disablePositionalTracking();
1632 // Release lock.
1633 lkFusionLock.unlock();
1634 }
1635 // Acquire write lock.
1636 std::unique_lock<std::shared_mutex> lkCameraLock(m_muCameraMutex);
1637 // Disable pose tracking.
1638 m_slCamera.disablePositionalTracking();
1639}

◆ SetPositionalPose()

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

Sets the pose of the positional tracking of the camera. XYZ will point in their respective directions according to ZED_COORD_SYSTEM defined in AutonomyConstants.h.

Warning: This method is slow and should not be called in a loop. Setting the pose will temporarily block the entire camera from grabbed or copying frames to new threads. This method should only be called occasionally when absolutely needed.

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. (0-360)
dYO- The tilt of the camera around the Y axis in degrees. (0-360)
dZO- The tilt of the camera around the Z axis in degrees. (0-360)
Returns
sl::ERROR_CODE - Whether or not the pose was set successfully.
Bug:
The ZEDSDK currently cannot handle resetting the positional pose with large translational (dX, dY, dZ) values without breaking positional tracking. This is because the values are floats and not doubles. To fix this I (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om), have decided to just handle the translation offsets internally. So when SetPositionalPose() is called is assigns the dX, dY, and dZ values to private member variables of this class, then the offsets are added the the pose in the PooledLinearCode() under the pose requests section. If StereoLabs fixes this in the future, I will go back to using the sl::Translation to reset positional tracking.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-08-27

Implements ZEDCamera.

1668{
1669 // Update offset member variables.
1670 m_dPoseOffsetX = dX - m_slCameraPose.getTranslation().x;
1671 m_dPoseOffsetY = dY - m_slCameraPose.getTranslation().y;
1672 m_dPoseOffsetZ = dZ - m_slCameraPose.getTranslation().z;
1673 // Find the angular distance from current and desired pose angles. This is complicated because zed uses different angle ranges.
1674 m_dPoseOffsetXO =
1675 numops::InputAngleModulus(numops::AngularDifference(numops::InputAngleModulus<double>(m_slCameraPose.getEulerAngles(false).x, 0.0, 360.0), dXO), 0.0, 360.0);
1676 m_dPoseOffsetYO =
1677 numops::InputAngleModulus(numops::AngularDifference(numops::InputAngleModulus<double>(m_slCameraPose.getEulerAngles(false).y, 0.0, 360.0), dYO), 0.0, 360.0);
1678 m_dPoseOffsetZO =
1679 numops::InputAngleModulus(numops::AngularDifference(numops::InputAngleModulus<double>(m_slCameraPose.getEulerAngles(false).z, 0.0, 360.0), dZO), 0.0, 360.0);
1680}
constexpr T InputAngleModulus(T tValue, T tMinValue, T tMaxValue)
Calculates the modulus of an input angle.
Definition NumberOperations.hpp:165
constexpr T AngularDifference(T tFirstValue, T tSecondValue)
Calculates the distance in degrees between two angles. This function accounts for wrap around so that...
Definition NumberOperations.hpp:204
Here is the call graph for this function:

◆ EnableSpatialMapping()

sl::ERROR_CODE ZEDCam::EnableSpatialMapping ( )
overridevirtual

Enabled the spatial mapping feature of the camera. Pose tracking will be enabled if it is not already.

Returns
sl::ERROR_CODE - Whether or not spatial mapping was successfully enabled.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-08-27

Reimplemented from ZEDCamera.

1692{
1693 // Create instance variables.
1694 sl::Pose slCameraPose;
1695 sl::ERROR_CODE slReturnCode = sl::ERROR_CODE::SUCCESS;
1696
1697 // Acquire read lock.
1698 std::shared_lock<std::shared_mutex> lkReadCameraLock(m_muCameraMutex);
1699 // Check if positional tracking is enabled.
1700 if (!m_slCamera.isPositionalTrackingEnabled())
1701 {
1702 // Release lock.
1703 lkReadCameraLock.unlock();
1704 // Enable positional tracking.
1705 slReturnCode = this->EnablePositionalTracking();
1706 }
1707 else
1708 {
1709 // Release lock.
1710 lkReadCameraLock.unlock();
1711 }
1712
1713 // Check if positional tracking is or was enabled successfully.
1714 if (slReturnCode == sl::ERROR_CODE::SUCCESS)
1715 {
1716 // Acquire write lock.
1717 std::unique_lock<std::shared_mutex> lkWriteCameraLock(m_muCameraMutex);
1718 // Call camera grab function once to ensure the camera is initialized with data.
1719 m_slCamera.grab(m_slRuntimeParams);
1720 // Enable spatial mapping.
1721 slReturnCode = m_slCamera.enableSpatialMapping(m_slSpatialMappingParams);
1722 // Release lock.
1723 lkWriteCameraLock.unlock();
1724
1725 // Check if positional tracking was enabled properly.
1726 if (slReturnCode != sl::ERROR_CODE::SUCCESS)
1727 {
1728 // Submit logger message.
1729 LOG_ERROR(logging::g_qSharedLogger,
1730 "Failed to enabled spatial mapping for camera {} ({})! sl::ERROR_CODE is: {}",
1731 sl::toString(m_slCameraModel).get(),
1732 m_unCameraSerialNumber,
1733 sl::toString(slReturnCode).get());
1734 }
1735 }
1736 else
1737 {
1738 // Submit logger message.
1739 LOG_ERROR(logging::g_qSharedLogger,
1740 "Failed to enabled spatial mapping for camera {} ({}) because positional tracking could not be enabled! sl::ERROR_CODE is: {}",
1741 sl::toString(m_slCameraModel).get(),
1742 m_unCameraSerialNumber,
1743 sl::toString(slReturnCode).get());
1744 }
1745
1746 // Return error code.
1747 return slReturnCode;
1748}
sl::ERROR_CODE EnablePositionalTracking(const float fExpectedCameraHeightFromFloorTolerance=constants::ZED_DEFAULT_FLOOR_PLANE_ERROR) override
Enable the positional tracking functionality of the camera.
Definition ZEDCam.cpp:1568
Here is the call graph for this function:
Here is the caller graph for this function:

◆ DisableSpatialMapping()

void ZEDCam::DisableSpatialMapping ( )
overridevirtual

Disabled the spatial mapping feature 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-08-27

Reimplemented from ZEDCamera.

1758{
1759 // Acquire write lock.
1760 std::unique_lock<std::shared_mutex> lkCameraLock(m_muCameraMutex);
1761 // Disable spatial mapping.
1762 m_slCamera.disableSpatialMapping();
1763}

◆ EnableObjectDetection()

sl::ERROR_CODE ZEDCam::EnableObjectDetection ( const bool  bEnableBatching = false)
overridevirtual

Enables the object detection and tracking feature of the camera.

Returns
sl::ERROR_CODE - Whether or not object detection/tracking was successfully enabled.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-08-27

Reimplemented from ZEDCamera.

1774{
1775 // Check if batching should be turned on.
1776 bEnableBatching ? m_slObjectDetectionBatchParams.enable = true : m_slObjectDetectionBatchParams.enable = false;
1777 // Give batch params to detection params.
1778 m_slObjectDetectionParams.batch_parameters = m_slObjectDetectionBatchParams;
1779
1780 // Acquire write lock.
1781 std::unique_lock<std::shared_mutex> lkCameraLock(m_muCameraMutex);
1782 // Enable object detection.
1783 sl::ERROR_CODE slReturnCode = m_slCamera.enableObjectDetection(m_slObjectDetectionParams);
1784 // Release lock.
1785 lkCameraLock.unlock();
1786
1787 // Check if positional tracking was enabled properly.
1788 if (slReturnCode != sl::ERROR_CODE::SUCCESS)
1789 {
1790 // Submit logger message.
1791 LOG_ERROR(logging::g_qSharedLogger,
1792 "Failed to enabled object detection for camera {} ({})! sl::ERROR_CODE is: {}",
1793 sl::toString(m_slCameraModel).get(),
1794 m_unCameraSerialNumber,
1795 sl::toString(slReturnCode).get());
1796 }
1797
1798 // Return error code.
1799 return slReturnCode;
1800}
Here is the call graph for this function:
Here is the caller graph for this function:

◆ DisableObjectDetection()

void ZEDCam::DisableObjectDetection ( )
overridevirtual

Disables the object detection and tracking feature 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-08-27

Reimplemented from ZEDCamera.

1810{
1811 // Acquire write lock.
1812 std::unique_lock<std::shared_mutex> lkCameraLock(m_muCameraMutex);
1813 // Disable object detection and tracking.
1814 m_slCamera.disableObjectDetection();
1815}

◆ GetCameraIsOpen()

bool ZEDCam::GetCameraIsOpen ( )
overridevirtual

Accessor for the current status of the camera.

Returns
true - Camera is currently opened and functional.
false - Camera is not opened and/or connected.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-08-27

Implements Camera< cv::Mat >.

1827{
1828 // Acquire read lock.
1829 std::shared_lock<std::shared_mutex> lkCameraLock(m_muCameraMutex);
1830 return m_slCamera.isOpened();
1831}
Here is the caller graph for this function:

◆ GetUsingGPUMem()

bool ZEDCam::GetUsingGPUMem ( ) const
overridevirtual

Accessor for if this ZED is storing it's frames in GPU memory.

Returns
true - Using GPU memory for mats.
false - Using CPU memory for mats.
Author
ClayJay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-09-09

Reimplemented from ZEDCamera.

1843{
1844 // Check if we are using GPU memory.
1845 return m_slMemoryType == sl::MEM::GPU;
1846}

◆ GetCameraModel()

std::string ZEDCam::GetCameraModel ( )
overridevirtual

Accessor for the model enum from the ZEDSDK and represents the camera model as a string.

Returns
std::string - The model of the zed camera. Possible values: ZED, ZED_MINI, ZED_2, ZED_2i, ZED_X, ZED_X_MINI, UNDEFINED_UNKNOWN
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-08-27

Implements ZEDCamera.

1858{
1859 // Acquire read lock.
1860 std::shared_lock<std::shared_mutex> lkCameraLock(m_muCameraMutex);
1861 // Check if the camera is opened.
1862 if (m_slCamera.isOpened())
1863 {
1864 // Release lock.
1865 lkCameraLock.unlock();
1866 // Convert camera model to a string and return.
1867 return sl::toString(m_slCameraModel).get();
1868 }
1869 else
1870 {
1871 // Release lock.
1872 lkCameraLock.unlock();
1873 // Return the model string to show camera isn't opened.
1874 return "NOT_OPENED";
1875 }
1876}
Here is the caller graph for this function:

◆ GetCameraSerial()

unsigned int ZEDCam::GetCameraSerial ( )
overridevirtual

Accessor for the camera's serial number.

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
2023-08-27

Reimplemented from ZEDCamera.

1887{
1888 // Return the model string to show camera isn't opened.
1889 return m_unCameraSerialNumber;
1890}
Here is the caller graph for this function:

◆ RequestPositionalPoseCopy()

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

Requests the current pose of the camera relative to it's start pose or the origin of the set pose. Puts a Pose pointer into a queue so a copy of a pose from the camera can be written to it. If positional tracking is not enabled, this method will return false and the ZEDCam::Pose may be uninitialized.

Parameters
stPose- A reference to the ZEDCam::Pose object to copy the current camera pose to.
Returns
std::future<bool> - A future that should be waited on before the passed in sl::Pose is used. Value will be true if pose was successfully retrieved.
Note
If this camera is acting as the ZEDSDK Fusion master instance, then the positional pose returned will be from the Fusion instance. aka The Fused GNSS and visual inertial odometry will be returned.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-08-27

Implements ZEDCamera.

1908{
1909 // Acquire read lock.
1910 std::shared_lock<std::shared_mutex> lkCameraLock(m_muCameraMutex);
1911 // Check if positional tracking has been enabled.
1912 if (m_slCamera.isPositionalTrackingEnabled())
1913 {
1914 // Release lock.
1915 lkCameraLock.unlock();
1916 // Assemble the data container.
1917 containers::DataFetchContainer<Pose> stContainer(stPose);
1918
1919 // Acquire lock on pose copy queue.
1920 std::unique_lock<std::shared_mutex> lkSchedulers(m_muPoolScheduleMutex);
1921 // Append pose fetch container to the schedule queue.
1922 m_qPoseCopySchedule.push(stContainer);
1923 // Release lock on the pose schedule queue.
1924 lkSchedulers.unlock();
1925
1926 // Check if pose queue toggle has already been set.
1927 if (!m_bPosesQueued.load(ATOMIC_MEMORY_ORDER_METHOD))
1928 {
1929 // Signify that the pose queue is not empty.
1930 m_bPosesQueued.store(true, ATOMIC_MEMORY_ORDER_METHOD);
1931 }
1932
1933 // Return the future from the promise stored in the container.
1934 return stContainer.pCopiedDataStatus->get_future();
1935 }
1936 else
1937 {
1938 // Release lock.
1939 lkCameraLock.unlock();
1940 // Submit logger message.
1941 LOG_WARNING(logging::g_qSharedLogger, "Attempted to get ZED positional pose but positional tracking is not enabled or is still initializing!");
1942
1943 // Create dummy promise to return the future.
1944 std::promise<bool> pmDummyPromise;
1945 std::future<bool> fuDummyFuture = pmDummyPromise.get_future();
1946 // Set future value.
1947 pmDummyPromise.set_value(false);
1948
1949 // Return unsuccessful.
1950 return fuDummyFuture;
1951 }
1952}
This struct is used to carry references to any datatype for scheduling and copying....
Definition FetchContainers.hpp:162

◆ RequestFusionGeoPoseCopy()

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

Requests the current geo pose of the camera. This method should be used to retrieve ONLY the GNSS data from the ZEDSDK's Fusion module. Puts a GeoPose pointer into a queue so a copy of a GeoPose from the camera can be written to it. If positional tracking or fusion is disabled for this camera, then this method will return false and the sl::GeoPose may be uninitialized.

Parameters
slGeoPose- A reference to the sl::GeoPose object to copy the current geo pose to.
Returns
std::future<bool> - A future that should be waited on before the passed in sl::GeoPose is used. Value will be true if geo pose was successfully retrieved.
Note
This camera must be a Fusion Master and the NavBoard must be giving accurate info to the camera for this to be functional.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2024-01-25

Implements ZEDCamera.

1970{
1971 // Acquire read lock.
1972 std::shared_lock<std::shared_mutex> lkCameraLock(m_muCameraMutex);
1973 // Check if positional tracking has been enabled.
1974 if (m_bCameraIsFusionMaster && m_slCamera.isPositionalTrackingEnabled())
1975 {
1976 // Release lock.
1977 lkCameraLock.unlock();
1978 // Assemble the data container.
1979 containers::DataFetchContainer<sl::GeoPose> stContainer(slGeoPose);
1980
1981 // Acquire lock on frame copy queue.
1982 std::unique_lock<std::shared_mutex> lkSchedulers(m_muPoolScheduleMutex);
1983 // Append frame fetch container to the schedule queue.
1984 m_qGeoPoseCopySchedule.push(stContainer);
1985 // Release lock on the frame schedule queue.
1986 lkSchedulers.unlock();
1987
1988 // Check if pose queue toggle has already been set.
1989 if (!m_bGeoPosesQueued.load(ATOMIC_MEMORY_ORDER_METHOD))
1990 {
1991 // Signify that the pose queue is not empty.
1992 m_bGeoPosesQueued.store(true, ATOMIC_MEMORY_ORDER_METHOD);
1993 }
1994
1995 // Return the future from the promise stored in the container.
1996 return stContainer.pCopiedDataStatus->get_future();
1997 }
1998 else
1999 {
2000 // Release lock.
2001 lkCameraLock.unlock();
2002 // Submit logger message.
2003 LOG_WARNING(logging::g_qSharedLogger,
2004 "Attempted to get ZED FUSION geo pose but positional tracking is not enabled and/or this camera was not initialized as a Fusion Master!");
2005
2006 // Create dummy promise to return the future.
2007 std::promise<bool> pmDummyPromise;
2008 std::future<bool> fuDummyFuture = pmDummyPromise.get_future();
2009 // Set future value.
2010 pmDummyPromise.set_value(false);
2011
2012 // Return unsuccessful.
2013 return fuDummyFuture;
2014 }
2015}

◆ RequestFloorPlaneCopy()

std::future< bool > ZEDCam::RequestFloorPlaneCopy ( sl::Plane &  slPlane)
overridevirtual

Requests the current floor plane of the camera relative to it's current pose. Puts a Plane pointer into a queue so a copy of the floor plane from the camera can be written to it. If positional tracking is not enabled, this method will return false and the sl::Plane may be uninitialized.

Parameters
slPlane- A reference to the sl::Plane object to copy the current camera floor plane to.
Returns
std::future<bool> - A future that should be waited on before the passed in sl::Plane is used. Value will be true if data 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-10-22

Reimplemented from ZEDCamera.

2030{
2031 // Acquire read lock.
2032 std::shared_lock<std::shared_mutex> lkCameraLock(m_muCameraMutex);
2033 // Check if positional tracking has been enabled.
2034 if (m_slCamera.isPositionalTrackingEnabled())
2035 {
2036 // Release lock.
2037 lkCameraLock.unlock();
2038 // Assemble the data container.
2039 containers::DataFetchContainer<sl::Plane> stContainer(slPlane);
2040
2041 // Acquire lock on pose copy queue.
2042 std::unique_lock<std::shared_mutex> lkSchedulers(m_muPoolScheduleMutex);
2043 // Append data fetch container to the schedule queue.
2044 m_qFloorCopySchedule.push(stContainer);
2045 // Release lock on the pose schedule queue.
2046 lkSchedulers.unlock();
2047
2048 // Check if pose queue toggle has already been set.
2049 if (!m_bFloorsQueued.load(std::memory_order_relaxed))
2050 {
2051 // Signify that the pose queue is not empty.
2052 m_bFloorsQueued.store(true, std::memory_order_relaxed);
2053 }
2054
2055 // Return the future from the promise stored in the container.
2056 return stContainer.pCopiedDataStatus->get_future();
2057 }
2058 else
2059 {
2060 // Release lock.
2061 lkCameraLock.unlock();
2062 // Submit logger message.
2063 LOG_WARNING(logging::g_qSharedLogger, "Attempted to get ZED floor plane but positional tracking is not enabled!");
2064
2065 // Create dummy promise to return the future.
2066 std::promise<bool> pmDummyPromise;
2067 std::future<bool> fuDummyFuture = pmDummyPromise.get_future();
2068 // Set future value.
2069 pmDummyPromise.set_value(false);
2070
2071 // Return unsuccessful.
2072 return fuDummyFuture;
2073 }
2074}

◆ GetPositionalTrackingEnabled()

bool ZEDCam::GetPositionalTrackingEnabled ( )
overridevirtual

Accessor for if the positional tracking functionality of the camera has been enabled and functioning.

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
2023-08-27

Implements ZEDCamera.

2087{
2088 // Acquire read lock.
2089 std::shared_lock<std::shared_mutex> lkCameraLock(m_muCameraMutex);
2090 return m_slCamera.isPositionalTrackingEnabled() && m_slCamera.getPositionalTrackingStatus().odometry_status == sl::ODOMETRY_STATUS::OK;
2091}

◆ GetPositionalTrackingState()

sl::PositionalTrackingStatus ZEDCam::GetPositionalTrackingState ( )
overridevirtual

Accessor for the current positional tracking status of the camera.

Returns
sl::PositionalTrackingStatus - The sl::PositionalTrackingStatus struct storing information about the current VIO 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-04-20

Reimplemented from ZEDCamera.

2103{
2104 // Acquire read lock.
2105 std::shared_lock<std::shared_mutex> lkCameraLock(m_muCameraMutex);
2106 return m_slCamera.getPositionalTrackingStatus();
2107}

◆ GetFusedPositionalTrackingState()

sl::FusedPositionalTrackingStatus ZEDCam::GetFusedPositionalTrackingState ( )
overridevirtual

Accessor for the current positional tracking status of the fusion instance.

Returns
sl::FusedPositionalTrackingStatus - The sl::FusedPositionalTrackingStatus struct storing information about the current VIO and GNSS fusion 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-04-22

Reimplemented from ZEDCamera.

2119{
2120 // Acquire read lock.
2121 std::shared_lock<std::shared_mutex> lkFusionLock(m_muFusionMutex);
2122 return m_slFusionInstance.getFusedPositionalTrackingStatus();
2123}

◆ GetSpatialMappingState()

sl::SPATIAL_MAPPING_STATE ZEDCam::GetSpatialMappingState ( )
overridevirtual

Accessor for the current state of the camera's spatial mapping feature.

Returns
sl::SPATIAL_MAPPING_STATE - The enum value of 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
2023-08-27

Reimplemented from ZEDCamera.

2134{
2135 // Acquire read lock.
2136 std::shared_lock<std::shared_mutex> lkCameraLock(m_muCameraMutex);
2137 // Return the current spatial mapping state of the camera.
2138 return m_slCamera.getSpatialMappingState();
2139}

◆ ExtractSpatialMapAsync()

sl::SPATIAL_MAPPING_STATE ZEDCam::ExtractSpatialMapAsync ( std::future< sl::Mesh > &  fuMeshFuture)
overridevirtual

Retrieve the built spatial map from the camera. Spatial mapping must be enabled. This method takes in an std::future<sl::FusedPointCloud> to eventually store the map in. It returns a enum code representing the successful scheduling of building the map. Any code other than SPATIAL_MAPPING_STATE::OK means the future will never be filled.

Parameters
std::future<sl::Mesh>- The future to eventually store the map in.
Returns
sl::SPATIAL_MAPPING_STATE - Whether or not the building of the map was successfully scheduled. Anything other than OK means the future will never be filled.
Author
clayjay3 (clayt.nosp@m.onra.nosp@m.ycowe.nosp@m.n@gm.nosp@m.ail.c.nosp@m.om)
Date
2023-08-27

Reimplemented from ZEDCamera.

2155{
2156 // Acquire read lock.
2157 std::shared_lock<std::shared_mutex> lkCameraLock(m_muCameraMutex);
2158 // Get and store current state of spatial mapping.
2159 sl::SPATIAL_MAPPING_STATE slReturnState = m_slCamera.getSpatialMappingState();
2160
2161 // Check if spatial mapping has been enabled and ready
2162 if (slReturnState == sl::SPATIAL_MAPPING_STATE::OK)
2163 {
2164 // Request that the ZEDSDK begin processing the spatial map for export.
2165 m_slCamera.requestSpatialMapAsync();
2166
2167 // Start an async thread to wait for spatial map processing to finish. Return resultant future object.
2168 fuMeshFuture = std::async(std::launch::async,
2169 [this]()
2170 {
2171 // Create instance variables.
2172 sl::Mesh slSpatialMap;
2173
2174 // Loop until map is finished generating.
2175 while (m_slCamera.getSpatialMapRequestStatusAsync() == sl::ERROR_CODE::FAILURE)
2176 {
2177 // Sleep for 10ms.
2178 std::this_thread::sleep_for(std::chrono::milliseconds(10));
2179 }
2180
2181 // Check if the spatial map was exported successfully.
2182 if (m_slCamera.getSpatialMapRequestStatusAsync() == sl::ERROR_CODE::SUCCESS)
2183 {
2184 // Get and store the spatial map.
2185 m_slCamera.retrieveSpatialMapAsync(slSpatialMap);
2186
2187 // Return spatial map.
2188 return slSpatialMap;
2189 }
2190 else
2191 {
2192 // Submit logger message.
2193 LOG_ERROR(logging::g_qSharedLogger,
2194 "Failed to extract ZED spatial map. sl::ERROR_CODE is: {}",
2195 sl::toString(m_slCamera.getSpatialMapRequestStatusAsync()).get());
2196
2197 // Return empty point cloud.
2198 return sl::Mesh();
2199 }
2200 });
2201 }
2202 else
2203 {
2204 // Submit logger message.
2205 LOG_WARNING(logging::g_qSharedLogger, "ZED spatial mapping was never enabled, can't extract spatial map!");
2206 }
2207
2208 // Return current spatial mapping state.
2209 return slReturnState;
2210}

◆ GetObjectDetectionEnabled()

bool ZEDCam::GetObjectDetectionEnabled ( )
overridevirtual

Accessor for if the cameras object detection and tracking feature is enabled.

Returns
true - Object detection and tracking is enabled.
false - Object detection and 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
2023-08-27

Reimplemented from ZEDCamera.

2222{
2223 // Acquire read lock.
2224 std::shared_lock<std::shared_mutex> lkCameraLock(m_muCameraMutex);
2225 return m_slCamera.isObjectDetectionEnabled();
2226}

◆ RequestObjectsCopy()

std::future< bool > ZEDCam::RequestObjectsCopy ( std::vector< sl::ObjectData > &  vObjectData)
overridevirtual

Requests a current copy of the tracked objects from the camera. Puts a pointer to a vector containing sl::ObjectData into a queue so a copy of a frame from the camera can be written to it.

Parameters
vObjectData- A vector that will have data copied to it containing sl::ObjectData objects.
Returns
std::future<bool> - A future that should be waited on before the passed in vector is used. Value will be true if data 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-27

Reimplemented from ZEDCamera.

2240{
2241 // Acquire read lock.
2242 std::shared_lock<std::shared_mutex> lkCameraLock(m_muCameraMutex);
2243 // Check if object detection has been enabled.
2244 if (m_slCamera.isObjectDetectionEnabled())
2245 {
2246 // Release lock.
2247 lkCameraLock.unlock();
2248 // Assemble the data container.
2250
2251 // Acquire lock on object copy queue.
2252 std::unique_lock<std::shared_mutex> lkSchedulers(m_muPoolScheduleMutex);
2253 // Append data fetch container to the schedule queue.
2254 m_qObjectDataCopySchedule.push(stContainer);
2255 // Release lock on the object schedule queue.
2256 lkSchedulers.unlock();
2257
2258 // Check if objects queue toggle has already been set.
2259 if (!m_bObjectsQueued.load(ATOMIC_MEMORY_ORDER_METHOD))
2260 {
2261 // Signify that the objects queue is not empty.
2262 m_bObjectsQueued.store(true, ATOMIC_MEMORY_ORDER_METHOD);
2263 }
2264
2265 // Return the future from the promise stored in the container.
2266 return stContainer.pCopiedDataStatus->get_future();
2267 }
2268 else
2269 {
2270 // Release lock.
2271 lkCameraLock.unlock();
2272 // Submit logger message.
2273 LOG_WARNING(logging::g_qSharedLogger, "Attempted to get ZED object data but object detection/tracking is not enabled!");
2274
2275 // Create dummy promise to return the future.
2276 std::promise<bool> pmDummyPromise;
2277 std::future<bool> fuDummyFuture = pmDummyPromise.get_future();
2278 // Set future value.
2279 pmDummyPromise.set_value(false);
2280
2281 // Return unsuccessful.
2282 return fuDummyFuture;
2283 }
2284}

◆ RequestBatchedObjectsCopy()

std::future< bool > ZEDCam::RequestBatchedObjectsCopy ( std::vector< sl::ObjectsBatch > &  vBatchedObjectData)
overridevirtual

If batching is enabled, this requests the normal objects and passes them to the the internal batching queue of the zed api. This performs short-term re-identification with deep learning and trajectories filtering. Batching must have been set to enabled when EnableObjectDetection() was called. Most of the time the vector will be empty and will be filled every ZED_OBJDETECTION_BATCH_LATENCY.

Parameters
vBatchedObjectData- A vector containing objects of sl::ObjectsBatch object that will have object data copied to.
Returns
std::future<bool> - A future that should be waited on before the passed in vector is used. Value will be true if data 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-30

Reimplemented from ZEDCamera.

2302{
2303 // Acquire read lock.
2304 std::shared_lock<std::shared_mutex> lkCameraLock(m_muCameraMutex);
2305 // Check if object detection and batching has been enabled.
2306 if (m_slCamera.isObjectDetectionEnabled() && m_slObjectDetectionBatchParams.enable)
2307 {
2308 // Release lock.
2309 lkCameraLock.unlock();
2310 // Assemble the data container.
2311 containers::DataFetchContainer<std::vector<sl::ObjectsBatch>> stContainer(vBatchedObjectData);
2312
2313 // Acquire lock on batched object copy queue.
2314 std::unique_lock<std::shared_mutex> lkSchedulers(m_muPoolScheduleMutex);
2315 // Append data fetch container to the schedule queue.
2316 m_qObjectBatchedDataCopySchedule.push(stContainer);
2317 // Release lock on the data schedule queue.
2318 lkSchedulers.unlock();
2319
2320 // Check if objects queue toggle has already been set.
2321 if (!m_bBatchedObjectsQueued.load(ATOMIC_MEMORY_ORDER_METHOD))
2322 {
2323 // Signify that the objects queue is not empty.
2324 m_bBatchedObjectsQueued.store(true, ATOMIC_MEMORY_ORDER_METHOD);
2325 }
2326
2327 // Return the future from the promise stored in the container.
2328 return stContainer.pCopiedDataStatus->get_future();
2329 }
2330 else
2331 {
2332 // Release lock.
2333 lkCameraLock.unlock();
2334 // Submit logger message.
2335 LOG_WARNING(logging::g_qSharedLogger, "Attempted to get ZED batched object data but object detection/tracking is not enabled!");
2336
2337 // Create dummy promise to return the future.
2338 std::promise<bool> pmDummyPromise;
2339 std::future<bool> fuDummyFuture = pmDummyPromise.get_future();
2340 // Set future value.
2341 pmDummyPromise.set_value(false);
2342
2343 // Return unsuccessful.
2344 return fuDummyFuture;
2345 }
2346}

◆ ThreadedContinuousCode()

void ZEDCam::ThreadedContinuousCode ( )
overrideprivatevirtual

The code inside this private method runs in a separate thread, but still has access to this*. This method continuously calls the grab() function of the ZEDSDK, which updates all frames (RGB, depth, cloud) and all other data such as positional and spatial mapping. 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-01

Implements AutonomyThread< void >.

288{
289 // Acquire read lock for camera object.
290 std::shared_lock<std::shared_mutex> lkReadCameraLock(m_muCameraMutex);
291 // Check if camera is opened.
292 if (!m_slCamera.isOpened())
293 {
294 // Release lock.
295 lkReadCameraLock.unlock();
296
297 // If this is the first iteration of the thread the camera probably isn't present so stop thread to save resources.
298 if (this->GetThreadState() == AutonomyThreadState::eStarting)
299 {
300 // Shutdown threads for this ZEDCam.
301 this->RequestStop();
302 // Submit logger message.
303 LOG_CRITICAL(logging::g_qSharedLogger,
304 "Camera start was attempted for ZED camera with serial number {}, but camera never properly opened or it has been closed/rebooted!",
305 m_unCameraSerialNumber);
306 }
307 else
308 {
309 // Create instance variables.
310 static bool bReopenAlreadyChecked = false;
311 std::chrono::time_point tmCurrentTime = std::chrono::system_clock::now();
312 // Convert time point to seconds since epoch
313 int nTimeSinceEpoch = std::chrono::duration_cast<std::chrono::seconds>(tmCurrentTime.time_since_epoch()).count();
314
315 // Only try to reopen camera every 5 seconds.
316 if (nTimeSinceEpoch % 5 == 0 && !bReopenAlreadyChecked)
317 {
318 // Acquire write lock for camera object.
319 std::unique_lock<std::shared_mutex> lkWriteCameraLock(m_muCameraMutex);
320 // Attempt to reopen camera.
321 sl::ERROR_CODE slReturnCode = m_slCamera.open(m_slCameraParams);
322 // Release lock.
323 lkWriteCameraLock.unlock();
324
325 // Check if camera was reopened.
326 if (slReturnCode == sl::ERROR_CODE::SUCCESS)
327 {
328 // Submit logger message.
329 LOG_INFO(logging::g_qSharedLogger, "ZED stereo camera with serial number {} has been reconnected and reopened!", m_unCameraSerialNumber);
330
331 // Check if this camera is a fusion master.
332 if (m_bCameraIsFusionMaster)
333 {
334 // Acquire write lock for camera object.
335 std::unique_lock<std::shared_mutex> lkWriteCameraLock(m_muCameraMutex);
336 // Enable odometry publishing for this ZED camera.
337 m_slCamera.startPublishing();
338 // Release lock.
339 lkWriteCameraLock.unlock();
340 }
341
342 // Check if positional tracking was enabled.
343 if (!m_slCamera.isPositionalTrackingEnabled())
344 {
345 slReturnCode = this->EnablePositionalTracking();
346 }
347 else
348 {
349 // Submit logger message.
350 LOG_ERROR(logging::g_qSharedLogger,
351 "After reopening ZED stereo camera with serial number {}, positional tracking failed to reinitialize. sl::ERROR_CODE is: {}",
352 m_unCameraSerialNumber,
353 sl::toString(slReturnCode).get());
354 }
355 // Check if spatial mapping was enabled.
356 if (m_slCamera.getSpatialMappingState() != sl::SPATIAL_MAPPING_STATE::OK)
357 {
358 slReturnCode = this->EnableSpatialMapping();
359 }
360 else
361 {
362 // Submit logger message.
363 LOG_ERROR(logging::g_qSharedLogger,
364 "After reopening ZED stereo camera with serial number {}, spatial mapping failed to reinitialize. sl::ERROR_CODE is: {}",
365 m_unCameraSerialNumber,
366 sl::toString(slReturnCode).get());
367 }
368 // Check if object detection was enabled.
369 if (!m_slCamera.isObjectDetectionEnabled())
370 {
371 slReturnCode = this->EnableObjectDetection();
372 }
373 else
374 {
375 // Submit logger message.
376 LOG_ERROR(logging::g_qSharedLogger,
377 "After reopening ZED stereo camera with serial number {}, object detection failed to reinitialize. sl::ERROR_CODE is: {}",
378 m_unCameraSerialNumber,
379 sl::toString(slReturnCode).get());
380 }
381 }
382 else
383 {
384 // Submit logger message.
385 LOG_WARNING(logging::g_qSharedLogger,
386 "Attempt to reopen ZED stereo camera with serial number {} has failed! Trying again in 5 seconds...",
387 m_unCameraSerialNumber);
388 }
389
390 // Set toggle.
391 bReopenAlreadyChecked = true;
392 }
393 else if (nTimeSinceEpoch % 5 != 0)
394 {
395 // Reset toggle.
396 bReopenAlreadyChecked = false;
397 }
398 }
399 }
400 else
401 {
402 // Release lock.
403 lkReadCameraLock.unlock();
404 // Acquire write lock for camera object.
405 std::unique_lock<std::shared_mutex> lkWriteCameraLock(m_muCameraMutex);
406 // Call generalized update method of zed api.
407 sl::ERROR_CODE slReturnCode = m_slCamera.grab(m_slRuntimeParams);
408 // Release camera lock.
409 lkWriteCameraLock.unlock();
410
411 // Check if this camera is the fusion master instance. Feed data to sl::Fusion.
412 if (m_bCameraIsFusionMaster)
413 {
414 // Acquire write lock.
415 std::unique_lock<std::shared_mutex> lkFusionLock(m_muFusionMutex);
416 // Call generalized process method of Fusion instance.
417 sl::FUSION_ERROR_CODE slReturnCode = m_slFusionInstance.process();
418 // Release lock.
419 lkFusionLock.unlock();
420
421 // Check if fusion data was processed correctly.
422 if (slReturnCode != sl::FUSION_ERROR_CODE::SUCCESS && slReturnCode != sl::FUSION_ERROR_CODE::NO_NEW_DATA_AVAILABLE)
423 {
424 // Submit logger message.
425 LOG_WARNING(logging::g_qSharedLogger,
426 "Unable to process fusion data for camera {} ({})! sl::FUSION_ERROR_CODE is: {}",
427 sl::toString(m_slCameraModel).get(),
428 m_unCameraSerialNumber,
429 sl::toString(slReturnCode).get());
430 }
431 }
432
433 // Check if new frame was computed successfully.
434 if (slReturnCode == sl::ERROR_CODE::SUCCESS)
435 {
436 // Check if normal frames have been requested.
437 if (m_bNormalFramesQueued.load(ATOMIC_MEMORY_ORDER_METHOD))
438 {
439 // Grab regular image and store it in member variable.
440 slReturnCode = m_slCamera.retrieveImage(m_slFrame, constants::ZED_RETRIEVE_VIEW, m_slMemoryType, sl::Resolution(m_nPropResolutionX, m_nPropResolutionY));
441 // Check that the regular frame was retrieved successfully.
442 if (slReturnCode != sl::ERROR_CODE::SUCCESS)
443 {
444 // Submit logger message.
445 LOG_WARNING(logging::g_qSharedLogger,
446 "Unable to retrieve new frame image for stereo camera {} ({})! sl::ERROR_CODE is: {}",
447 sl::toString(m_slCameraModel).get(),
448 m_unCameraSerialNumber,
449 sl::toString(slReturnCode).get());
450 }
451 }
452
453 // Check if depth frames have been requested.
454 if (m_bDepthFramesQueued.load(ATOMIC_MEMORY_ORDER_METHOD))
455 {
456 // Grab depth measure and store it in member variable.
457 slReturnCode = m_slCamera.retrieveMeasure(m_slDepthMeasure, m_slDepthMeasureType, m_slMemoryType, sl::Resolution(m_nPropResolutionX, m_nPropResolutionY));
458 // Check that the regular frame was retrieved successfully.
459 if (slReturnCode != sl::ERROR_CODE::SUCCESS)
460 {
461 // Submit logger message.
462 LOG_WARNING(logging::g_qSharedLogger,
463 "Unable to retrieve new depth measure for stereo camera {} ({})! sl::ERROR_CODE is: {}",
464 sl::toString(m_slCameraModel).get(),
465 m_unCameraSerialNumber,
466 sl::toString(slReturnCode).get());
467 }
468
469 // Grab depth grayscale image and store it in member variable.
470 slReturnCode = m_slCamera.retrieveImage(m_slDepthImage, sl::VIEW::DEPTH, m_slMemoryType, sl::Resolution(m_nPropResolutionX, m_nPropResolutionY));
471 // Check that the regular frame was retrieved successfully.
472 if (slReturnCode != sl::ERROR_CODE::SUCCESS)
473 {
474 // Submit logger message.
475 LOG_WARNING(logging::g_qSharedLogger,
476 "Unable to retrieve new depth image for stereo camera {} ({})! sl::ERROR_CODE is: {}",
477 sl::toString(m_slCameraModel).get(),
478 m_unCameraSerialNumber,
479 sl::toString(slReturnCode).get());
480 }
481 }
482
483 // Check if point clouds have been requested.
484 if (m_bPointCloudsQueued.load(ATOMIC_MEMORY_ORDER_METHOD))
485 {
486 // Grab regular resized image and store it in member variable.
487 slReturnCode = m_slCamera.retrieveMeasure(m_slPointCloud, sl::MEASURE::XYZBGRA, m_slMemoryType, sl::Resolution(m_nPropResolutionX, m_nPropResolutionY));
488 // Check that the regular frame was retrieved successfully.
489 if (slReturnCode != sl::ERROR_CODE::SUCCESS)
490 {
491 // Submit logger message.
492 LOG_WARNING(logging::g_qSharedLogger,
493 "Unable to retrieve new point cloud for stereo camera {} ({})! sl::ERROR_CODE is: {}",
494 sl::toString(m_slCameraModel).get(),
495 m_unCameraSerialNumber,
496 sl::toString(slReturnCode).get());
497 }
498 }
499
500 // Check if positional tracking is enabled.
501 if (m_slCamera.isPositionalTrackingEnabled())
502 {
503 // Check if poses have been requested.
504 if (m_bPosesQueued.load(ATOMIC_MEMORY_ORDER_METHOD))
505 {
506 // Create instance variable for storing the result of retrieving the pose.
507 sl::POSITIONAL_TRACKING_STATE slPoseTrackReturnCode;
508
509 // Check if this camera has Fusion instance enabled.
510 if (m_bCameraIsFusionMaster)
511 {
512 // Get tracking pose from Fusion.
513 slPoseTrackReturnCode = m_slFusionInstance.getPosition(m_slCameraPose, sl::REFERENCE_FRAME::WORLD);
514 }
515 else
516 {
517 // Get normal vision tracking pose from camera.
518 slPoseTrackReturnCode = m_slCamera.getPosition(m_slCameraPose, sl::REFERENCE_FRAME::WORLD);
519 }
520 // Check that the regular frame was retrieved successfully.
521 if (slPoseTrackReturnCode != sl::POSITIONAL_TRACKING_STATE::OK)
522 {
523 // Submit logger message.
524 LOG_WARNING(logging::g_qSharedLogger,
525 "Unable to retrieve new positional tracking pose for stereo camera {} ({})! sl::POSITIONAL_TRACKING_STATE is: {}",
526 sl::toString(m_slCameraModel).get(),
527 m_unCameraSerialNumber,
528 sl::toString(slPoseTrackReturnCode).get());
529 }
530 }
531
532 // Check if geo poses have been requested.
533 if (m_bCameraIsFusionMaster && m_bGeoPosesQueued.load(ATOMIC_MEMORY_ORDER_METHOD))
534 {
535 // Get the fused geo pose from the camera.
536 sl::GNSS_FUSION_STATUS slGeoPoseTrackReturnCode = m_slFusionInstance.getGeoPose(m_slFusionGeoPose);
537 // Check that the geo pose was retrieved successfully.
538 if (slGeoPoseTrackReturnCode != sl::GNSS_FUSION_STATUS::OK && slGeoPoseTrackReturnCode != sl::GNSS_FUSION_STATUS::CALIBRATION_IN_PROGRESS)
539 {
540 // Submit logger message.
541 LOG_WARNING(logging::g_qSharedLogger,
542 "Geo pose tracking state for stereo camera {} ({}) is suboptimal! sl::GNSS_FUSION_STATUS is: {}",
543 sl::toString(m_slCameraModel).get(),
544 m_unCameraSerialNumber,
545 sl::toString(slGeoPoseTrackReturnCode).get());
546 }
547 }
548
549 // Check if floor planes are being requested.
550 if (m_bFloorsQueued.load(ATOMIC_MEMORY_ORDER_METHOD))
551 {
552 // Get the current pose of the camera.
553 slReturnCode = m_slCamera.findFloorPlane(m_slFloorPlane,
554 m_slFloorTrackingTransform,
555 m_slCameraPose.getTranslation().y,
556 m_slCameraPose.getRotationMatrix(),
557 m_fExpectedCameraHeightFromFloorTolerance);
558 // Check that the regular frame was retrieved successfully.
559 if (slReturnCode != sl::ERROR_CODE::SUCCESS)
560 {
561 // Submit logger message.
562 LOG_WARNING(logging::g_qSharedLogger,
563 "Unable to retrieve new floor plane for stereo camera {} ({})! sl::ERROR_CODE is: {}",
564 sl::toString(m_slCameraModel).get(),
565 m_unCameraSerialNumber,
566 sl::toString(slReturnCode).get());
567 }
568 }
569 }
570
571 // Check if object detection is enabled.
572 if (m_slCamera.isObjectDetectionEnabled())
573 {
574 // Check if objects have been requested.
575 if (m_bObjectsQueued.load(ATOMIC_MEMORY_ORDER_METHOD))
576 {
577 // Get updated objects from camera.
578 slReturnCode = m_slCamera.retrieveObjects(m_slDetectedObjects);
579 // Check that the regular frame was retrieved successfully.
580 if (slReturnCode != sl::ERROR_CODE::SUCCESS)
581 {
582 // Submit logger message.
583 LOG_WARNING(logging::g_qSharedLogger,
584 "Unable to retrieve new object data for stereo camera {} ({})! sl::ERROR_CODE is: {}",
585 sl::toString(m_slCameraModel).get(),
586 m_unCameraSerialNumber,
587 sl::toString(slReturnCode).get());
588 }
589 }
590
591 // Check if batched object data is enabled.
592 if (m_slObjectDetectionBatchParams.enable)
593 {
594 // Check if batched objects have been requested.
595 if (m_bBatchedObjectsQueued.load(ATOMIC_MEMORY_ORDER_METHOD))
596 {
597 // Get updated batched objects from camera.
598 slReturnCode = m_slCamera.getObjectsBatch(m_slDetectedObjectsBatched);
599 // Check that the regular frame was retrieved successfully.
600 if (slReturnCode != sl::ERROR_CODE::SUCCESS)
601 {
602 // Submit logger message.
603 LOG_WARNING(logging::g_qSharedLogger,
604 "Unable to retrieve new batched object data for stereo camera {} ({})! sl::ERROR_CODE is: {}",
605 sl::toString(m_slCameraModel).get(),
606 m_unCameraSerialNumber,
607 sl::toString(slReturnCode).get());
608 }
609 }
610 }
611 }
612 // Detection not enabled, but got requests.
613 else if (m_bObjectsQueued.load(std::memory_order_relaxed) || m_bBatchedObjectsQueued.load(std::memory_order_relaxed))
614 {
615 // Submit logger message.
616 LOG_WARNING(logging::g_qSharedLogger,
617 "Unable to retrieve new object data for stereo camera {} ({})! Object detection is disabled!",
618 sl::toString(m_slCameraModel).get(),
619 m_unCameraSerialNumber);
620 }
621 }
622 else
623 {
624 // Submit logger message.
625 LOG_ERROR(logging::g_qSharedLogger,
626 "Unable to update stereo camera {} ({}) frames, measurements, and sensors! sl::ERROR_CODE is: {}. Closing camera...",
627 sl::toString(m_slCameraModel).get(),
628 m_unCameraSerialNumber,
629 sl::toString(slReturnCode).get());
630
631 // Release camera resources.
632 m_slCamera.close();
633 }
634 }
635
636 // Acquire a shared_lock on the frame copy queue.
637 std::shared_lock<std::shared_mutex> lkSchedulers(m_muPoolScheduleMutex);
638 // Check if any requests have been made.
639 if (!m_qFrameCopySchedule.empty() || !m_qGPUFrameCopySchedule.empty() || !m_qCustomBoxIngestSchedule.empty() || !m_qPoseCopySchedule.empty() ||
640 !m_qGeoPoseCopySchedule.empty() || m_qFloorCopySchedule.size() || !m_qObjectDataCopySchedule.empty() || !m_qObjectBatchedDataCopySchedule.empty())
641 {
642 // Add the length of all queues together to determine how many tasks need to be run.
643 size_t siTotalQueueLength = m_qFrameCopySchedule.size() + m_qGPUFrameCopySchedule.size() + m_qCustomBoxIngestSchedule.size() + m_qPoseCopySchedule.size() +
644 m_qGeoPoseCopySchedule.size() + m_qFloorCopySchedule.size() + m_qObjectDataCopySchedule.size() +
645 m_qObjectBatchedDataCopySchedule.size();
646
647 // Start the thread pool to copy member variables to requesting other threads. Num of tasks queued depends on number of member variables updates and requests.
648 this->RunDetachedPool(siTotalQueueLength, m_nNumFrameRetrievalThreads);
649
650 // Static bool for keeping track of reset toggle action.
651 static bool bQueueTogglesAlreadyReset = false;
652 // Get current time.
653 std::chrono::_V2::system_clock::duration tmCurrentTime = std::chrono::high_resolution_clock::now().time_since_epoch();
654 // Only reset once every couple seconds.
655 if (std::chrono::duration_cast<std::chrono::seconds>(tmCurrentTime).count() % 31 == 0 && !bQueueTogglesAlreadyReset)
656 {
657 // Reset queue counters.
658 m_bNormalFramesQueued.store(false, ATOMIC_MEMORY_ORDER_METHOD);
659 m_bDepthFramesQueued.store(false, ATOMIC_MEMORY_ORDER_METHOD);
660 m_bPointCloudsQueued.store(false, ATOMIC_MEMORY_ORDER_METHOD);
661 m_bPosesQueued.store(false, ATOMIC_MEMORY_ORDER_METHOD);
662 m_bGeoPosesQueued.store(false, ATOMIC_MEMORY_ORDER_METHOD);
663 m_bFloorsQueued.store(false, ATOMIC_MEMORY_ORDER_METHOD);
664 m_bObjectsQueued.store(false, ATOMIC_MEMORY_ORDER_METHOD);
665 m_bBatchedObjectsQueued.store(false, ATOMIC_MEMORY_ORDER_METHOD);
666
667 // Set reset toggle.
668 bQueueTogglesAlreadyReset = true;
669 }
670 // Crucial for toggle action. If time is not evenly devisable and toggles have previously been set, reset queue reset boolean.
671 else if (bQueueTogglesAlreadyReset)
672 {
673 // Reset reset toggle.
674 bQueueTogglesAlreadyReset = false;
675 }
676
677 // Wait for thread pool to finish.
678 this->JoinPool();
679 }
680
681 // Release lock on frame copy queue.
682 lkSchedulers.unlock();
683}
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
AutonomyThreadState GetThreadState() const
Accessor for the Threads State private member.
Definition AutonomyThread.hpp:214
sl::ERROR_CODE EnableSpatialMapping() override
Enabled the spatial mapping feature of the camera. Pose tracking will be enabled if it is not already...
Definition ZEDCam.cpp:1691
sl::ERROR_CODE EnableObjectDetection(const bool bEnableBatching=false) override
Enables the object detection and tracking feature of the camera.
Definition ZEDCam.cpp:1773
Here is the call graph for this function:

◆ PooledLinearCode()

void ZEDCam::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 queue filled by the Request methods.

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

Implements AutonomyThread< void >.

696{
698 // Frame queue.
700 // Check if we are using CPU or GPU mats.
701 if (m_slMemoryType == sl::MEM::CPU)
702 {
703 // Acquire mutex for getting frames out of the queue.
704 std::unique_lock<std::shared_mutex> lkFrameQueue(m_muFrameCopyMutex);
705 // Check if the queue is empty.
706 if (!m_qFrameCopySchedule.empty())
707 {
708 // Get frame container out of queue.
709 containers::FrameFetchContainer<cv::Mat> stContainer = m_qFrameCopySchedule.front();
710 // Pop out of queue.
711 m_qFrameCopySchedule.pop();
712 // Release lock.
713 lkFrameQueue.unlock();
714
715 // Determine which frame should be copied.
716 switch (stContainer.eFrameType)
717 {
718 case PIXEL_FORMATS::eBGRA: *(stContainer.pFrame) = imgops::ConvertSLMatToCVMat(m_slFrame); break;
719 case PIXEL_FORMATS::eDepthMeasure: *(stContainer.pFrame) = imgops::ConvertSLMatToCVMat(m_slDepthMeasure); break;
720 case PIXEL_FORMATS::eDepthImage: *(stContainer.pFrame) = imgops::ConvertSLMatToCVMat(m_slDepthImage); break;
721 case PIXEL_FORMATS::eXYZBGRA: *(stContainer.pFrame) = imgops::ConvertSLMatToCVMat(m_slPointCloud); break;
722 default: *(stContainer.pFrame) = imgops::ConvertSLMatToCVMat(m_slFrame); break;
723 }
724
725 // Signal future that the frame has been successfully retrieved.
726 stContainer.pCopiedFrameStatus->set_value(true);
727 }
728
729 // Check if anything has been added to the GPU queue.
730 if (!m_qGPUFrameCopySchedule.empty())
731 {
732 // Submit logger error.
733 LOG_ERROR(logging::g_qSharedLogger,
734 "ZEDCam ({}) is in CPU sl::Mat mode but a GPU mat has been added to the copy queue! Whichever thread queued the frame will now appear frozen if "
735 "future.get() is called. Either switch the camera to GPU Mat mode in AutonomyConstants.h or stop queueing frames of type cv::Mat.",
736 m_unCameraSerialNumber);
737 }
738 }
739 // Use GPU mat.
740 else
741 {
742 // Acquire mutex for getting frames out of the queue.
743 std::unique_lock<std::shared_mutex> lkFrameQueue(m_muFrameCopyMutex);
744 // Check if the queue is empty.
745 if (!m_qGPUFrameCopySchedule.empty())
746 {
747 // Get frame container out of queue.
748 containers::FrameFetchContainer<cv::cuda::GpuMat> stContainer = m_qGPUFrameCopySchedule.front();
749 // Pop out of queue.
750 m_qGPUFrameCopySchedule.pop();
751 // Release lock.
752 lkFrameQueue.unlock();
753
754 // Determine which frame should be copied.
755 switch (stContainer.eFrameType)
756 {
757 case PIXEL_FORMATS::eBGRA: *(stContainer.pFrame) = imgops::ConvertSLMatToGPUMat(m_slFrame); break;
758 case PIXEL_FORMATS::eDepthMeasure: *(stContainer.pFrame) = imgops::ConvertSLMatToGPUMat(m_slDepthMeasure); break;
759 case PIXEL_FORMATS::eDepthImage: *(stContainer.pFrame) = imgops::ConvertSLMatToGPUMat(m_slDepthImage); break;
760 case PIXEL_FORMATS::eXYZBGRA: *(stContainer.pFrame) = imgops::ConvertSLMatToGPUMat(m_slPointCloud); break;
761 default: *(stContainer.pFrame) = imgops::ConvertSLMatToGPUMat(m_slFrame); break;
762 }
763
764 // Signal future that the frame has been successfully retrieved.
765 stContainer.pCopiedFrameStatus->set_value(true);
766 }
767
768 // Check if anything has been added to the GPU queue.
769 if (!m_qFrameCopySchedule.empty())
770 {
771 // Submit logger error.
772 LOG_ERROR(logging::g_qSharedLogger,
773 "ZEDCam ({}) is in GPU sl::Mat mode but a CPU mat has been added to the copy queue! Whichever thread queued the frame will now appear frozen if "
774 "future.get() is called. Either switch the camera to GPU Mat mode in AutonomyConstants.h or stop queueing frames of type cv::cuda::GpuMat.",
775 m_unCameraSerialNumber);
776 }
777 }
778
780 // Pose queue.
782 // Acquire mutex for getting data out of the pose queue.
783 std::unique_lock<std::shared_mutex> lkPoseQueue(m_muPoseCopyMutex);
784 // Check if the queue is empty.
785 if (!m_qPoseCopySchedule.empty())
786 {
787 // Get pose container out of queue.
788 containers::DataFetchContainer<Pose> stContainer = m_qPoseCopySchedule.front();
789 // Pop out of queue.
790 m_qPoseCopySchedule.pop();
791 // Release lock.
792 lkPoseQueue.unlock();
793
794 // Rotate the ZED position coordinate frame to realign with the UTM global coordinate frame.
795 std::vector<numops::CoordinatePoint<double>> vPointCloud;
796 vPointCloud.emplace_back(m_slCameraPose.getTranslation().x, m_slCameraPose.getTranslation().y, m_slCameraPose.getTranslation().z);
797 // Get angle realignments.
798 double dNewXO = numops::InputAngleModulus<double>(m_slCameraPose.getEulerAngles(false).x + m_dPoseOffsetXO, 0.0, 360.0);
799 double dNewYO = numops::InputAngleModulus<double>(m_slCameraPose.getEulerAngles(false).y + m_dPoseOffsetYO, 0.0, 360.0);
800 double dNewZO = numops::InputAngleModulus<double>(m_slCameraPose.getEulerAngles(false).z + m_dPoseOffsetZO, 0.0, 360.0);
801 // Rotate coordinate frame.
802 numops::CoordinateFrameRotate3D(vPointCloud, m_dPoseOffsetXO, m_dPoseOffsetYO, m_dPoseOffsetZO);
803 // Repack values into pose.
804 Pose stPose(vPointCloud[0].tX + m_dPoseOffsetX, vPointCloud[0].tY + m_dPoseOffsetY, vPointCloud[0].tZ + m_dPoseOffsetZ, dNewXO, dNewYO, dNewZO);
805
806 // 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.
807 // // Check ZED coordinate system.
808 // switch (m_slCameraParams.coordinate_system)
809 // {
810 // case sl::COORDINATE_SYSTEM::LEFT_HANDED_Y_UP:
811 // {
812 // // Realign based in the signedness of this coordinate system. Z is backwards.
813 // stPose.stTranslation.dZ *= -1;
814 // break;
815 // }
816 // default:
817 // {
818 // // No need to flip signs for other coordinate systems.
819 // break;
820 // }
821 // }
822
823 // Copy pose.
824 *(stContainer.pData) = stPose;
825
826 // Signal future that the data has been successfully retrieved.
827 stContainer.pCopiedDataStatus->set_value(true);
828 }
829 else
830 {
831 // Release lock.
832 lkPoseQueue.unlock();
833 }
834
836 // GeoPose queue.
838 // Acquire mutex for getting data out of the pose queue.
839 std::unique_lock<std::shared_mutex> lkGeoPoseQueue(m_muGeoPoseCopyMutex);
840 // Check if the queue is empty.
841 if (!m_qGeoPoseCopySchedule.empty())
842 {
843 // Get pose container out of queue.
844 containers::DataFetchContainer<sl::GeoPose> stContainer = m_qGeoPoseCopySchedule.front();
845 // Pop out of queue.
846 m_qGeoPoseCopySchedule.pop();
847 // Release lock.
848 lkGeoPoseQueue.unlock();
849
850 // Copy pose.
851 *(stContainer.pData) = sl::GeoPose(m_slFusionGeoPose);
852
853 // Signal future that the data has been successfully retrieved.
854 stContainer.pCopiedDataStatus->set_value(true);
855 }
856 else
857 {
858 // Release lock.
859 lkGeoPoseQueue.unlock();
860 }
861
863 // Plane queue.
865 // Acquire mutex for getting frames out of the plane queue.
866 std::unique_lock<std::shared_mutex> lkPlaneQueue(m_muFloorCopyMutex);
867 // Check if the queue is empty.
868 if (!m_qFloorCopySchedule.empty())
869 {
870 // Get frame container out of queue.
871 containers::DataFetchContainer<sl::Plane> stContainer = m_qFloorCopySchedule.front();
872 // Pop out of queue.
873 m_qFloorCopySchedule.pop();
874 // Release lock.
875 lkPlaneQueue.unlock();
876
877 // Copy pose.
878 *(stContainer.pData) = sl::Plane(m_slFloorPlane);
879 }
880 else
881 {
882 // Release lock.
883 lkPlaneQueue.unlock();
884 }
885
887 // ObjectData queue.
889 // Acquire mutex for getting data out of the pose queue.
890 std::unique_lock<std::shared_mutex> lkObjectDataQueue(m_muObjectDataCopyMutex);
891 // Check if the queue is empty.
892 if (!m_qObjectDataCopySchedule.empty())
893 {
894 // Get frame container out of queue.
895 containers::DataFetchContainer<std::vector<sl::ObjectData>> stContainer = m_qObjectDataCopySchedule.front();
896 // Pop out of queue.
897 m_qObjectDataCopySchedule.pop();
898 // Release lock.
899 lkObjectDataQueue.unlock();
900
901 // Make copy of object vector. (Apparently the assignment operator actually does a deep copy)
902 *(stContainer.pData) = m_slDetectedObjects.object_list;
903
904 // Signal future that the data has been successfully retrieved.
905 stContainer.pCopiedDataStatus->set_value(true);
906 }
907 else
908 {
909 // Release lock.
910 lkObjectDataQueue.unlock();
911 }
912
914 // ObjectData Batched queue.
916 // Acquire mutex for getting data out of the pose queue.
917 std::unique_lock<std::shared_mutex> lkObjectBatchedDataQueue(m_muObjectBatchedDataCopyMutex);
918 // Check if the queue is empty.
919 if (!m_qObjectBatchedDataCopySchedule.empty())
920 {
921 // Get frame container out of queue.
922 containers::DataFetchContainer<std::vector<sl::ObjectsBatch>> stContainer = m_qObjectBatchedDataCopySchedule.front();
923 // Pop out of queue.
924 m_qObjectBatchedDataCopySchedule.pop();
925 // Release lock.
926 lkObjectBatchedDataQueue.unlock();
927
928 // Make copy of object vector. (Apparently the assignment operator actually does a deep copy)
929 *(stContainer.pData) = m_slDetectedObjectsBatched;
930
931 // Signal future that the data has been successfully retrieved.
932 stContainer.pCopiedDataStatus->set_value(true);
933 }
934 else
935 {
936 // Release lock.
937 lkObjectBatchedDataQueue.unlock();
938 }
939}
cv::cuda::GpuMat ConvertSLMatToGPUMat(sl::Mat &slInputMat)
Convert a ZEDSDK sl::Mat object into an OpenCV cv::cuda::GpuMat object. Keeps all Mat memory in GPU V...
Definition ImageOperations.hpp:127
cv::Mat ConvertSLMatToCVMat(sl::Mat &slInputMat)
Convert a ZEDSDK sl::Mat object into an OpenCV cv::Mat object. This copies the mat from GPU memory to...
Definition ImageOperations.hpp:106
constexpr void CoordinateFrameRotate3D(std::vector< CoordinatePoint< T > > &vPointCloud, const double dXRotationDegrees, const double dYRotationDegrees, const double dZRotationDegrees)
This method will rotate a list of 3D coordinate points a variable amount of degrees around the X,...
Definition NumberOperations.hpp:287
Here is the call graph for this function:

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