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.h
Go to the documentation of this file.
1
11#ifndef ZEDCAM_H
12#define ZEDCAM_H
13
14#include "../../interfaces/ZEDCamera.hpp"
15
17
19
20
30class ZEDCam : public ZEDCamera
31{
32 public:
34 // Declare public methods and member variables.
36
37 ZEDCam(const int nPropResolutionX,
38 const int nPropResolutionY,
39 const int nPropFramesPerSecond,
40 const double dPropHorizontalFOV,
41 const double dPropVerticalFOV,
42 const bool bEnableRecordingFlag = false,
43 const bool bExportSVORecordingFlag = false,
44 const float fMinSenseDistance = constants::ZED_DEFAULT_MINIMUM_DISTANCE,
45 const float fMaxSenseDistance = constants::ZED_DEFAULT_MAXIMUM_DISTANCE,
46 const bool bMemTypeGPU = false,
47 const bool bUseHalfDepthPrecision = false,
48 const bool bEnableFusionMaster = false,
49 const int nNumFrameRetrievalThreads = 10,
50 const unsigned int unCameraSerialNumber = 0);
51 ~ZEDCam();
52 std::future<bool> RequestFrameCopy(cv::Mat& cvFrame) override;
53 std::future<bool> RequestFrameCopy(cv::cuda::GpuMat& cvGPUFrame) override;
54 std::future<bool> RequestDepthCopy(cv::Mat& cvDepth, const bool bRetrieveMeasure = true) override;
55 std::future<bool> RequestDepthCopy(cv::cuda::GpuMat& cvGPUDepth, const bool bRetrieveMeasure = true) override;
56 std::future<bool> RequestPointCloudCopy(cv::Mat& cvPointCloud) override;
57 std::future<bool> RequestPointCloudCopy(cv::cuda::GpuMat& cvGPUPointCloud) override;
58 std::future<bool> RequestPositionalPoseCopy(Pose& stPose) override;
59 std::future<bool> RequestFusionGeoPoseCopy(sl::GeoPose& slGeoPose) override;
60 std::future<bool> RequestFloorPlaneCopy(sl::Plane& slPlane) override;
61 std::future<bool> RequestSensorsCopy(sl::SensorsData& slSensorsData) override;
62 std::future<bool> RequestObjectsCopy(std::vector<sl::ObjectData>& vObjectData) override;
63 std::future<bool> RequestBatchedObjectsCopy(std::vector<sl::ObjectsBatch>& vBatchedObjectData) override;
64 sl::ERROR_CODE ResetPositionalTracking() override;
65 sl::ERROR_CODE TrackCustomBoxObjects(std::vector<ZedObjectData>& vCustomObjects) override;
66 sl::ERROR_CODE RebootCamera() override;
67 sl::FUSION_ERROR_CODE SubscribeFusionToCameraUUID(sl::CameraIdentifier& slCameraUUID) override;
68 sl::CameraIdentifier PublishCameraToFusion() override;
69 sl::FUSION_ERROR_CODE IngestGPSDataToFusion(geoops::GPSCoordinate stNewGPSLocation) override;
70
72 // Setters for class member variables.
74
75 sl::ERROR_CODE EnablePositionalTracking(const float fExpectedCameraHeightFromFloorTolerance = constants::ZED_DEFAULT_FLOOR_PLANE_ERROR) override;
76 void DisablePositionalTracking() override;
77 void SetPositionalPose(const double dX, const double dY, const double dZ, const double dXO, const double dYO, const double dZO) override;
78 sl::ERROR_CODE EnableSpatialMapping() override;
79 void DisableSpatialMapping() override;
80 sl::ERROR_CODE EnableObjectDetection(const bool bEnableBatching = false) override;
81 void DisableObjectDetection() override;
82
84 // Getters.
86
87 bool GetCameraIsOpen() override;
88 bool GetUsingGPUMem() const override;
89 std::string GetCameraModel() override;
90 unsigned int GetCameraSerial() override;
91 bool GetPositionalTrackingEnabled() override;
92 sl::PositionalTrackingStatus GetPositionalTrackingState() override;
93 sl::FusedPositionalTrackingStatus GetFusedPositionalTrackingState() override;
94 sl::SPATIAL_MAPPING_STATE GetSpatialMappingState() override;
95 sl::SPATIAL_MAPPING_STATE ExtractSpatialMapAsync(std::future<sl::Mesh>& fuMeshFuture) override;
96 bool GetObjectDetectionEnabled() override;
97
98 private:
100 // Declare private member variables.
102
103 // ZED Camera specific.
104
105 sl::Camera m_slCamera;
106 std::shared_mutex m_muCameraMutex;
107 sl::InitParameters m_slCameraParams;
108 sl::RuntimeParameters m_slRuntimeParams;
109 sl::RecordingParameters m_slRecordingParams;
110 sl::Fusion m_slFusionInstance;
111 std::shared_mutex m_muFusionMutex;
112 sl::InitFusionParameters m_slFusionParams;
113 sl::MEASURE m_slDepthMeasureType;
114 sl::PositionalTrackingParameters m_slPoseTrackingParams;
115 sl::PositionalTrackingFusionParameters m_slFusionPoseTrackingParams;
116 sl::Pose m_slCameraPose;
117 sl::GeoPose m_slFusionGeoPose;
118 sl::Plane m_slFloorPlane;
119 sl::Transform m_slFloorTrackingTransform;
120 sl::SensorsData m_slSensorsData;
121 sl::SpatialMappingParameters m_slSpatialMappingParams;
122 sl::ObjectDetectionParameters m_slObjectDetectionParams;
123 sl::BatchParameters m_slObjectDetectionBatchParams;
124 sl::Objects m_slDetectedObjects;
125 std::vector<sl::ObjectsBatch> m_slDetectedObjectsBatched;
126 sl::MEM m_slMemoryType;
127 sl::MODEL m_slCameraModel;
128 float m_fExpectedCameraHeightFromFloorTolerance;
129 bool m_bCameraReopenAlreadyChecked;
130
131 // Pose tracking offsets. (ZEDSDK is broken and can't handle large translations internally)
132
133 double m_dPoseOffsetX;
134 double m_dPoseOffsetY;
135 double m_dPoseOffsetZ;
136 double m_dPoseOffsetXO;
137 double m_dPoseOffsetYO;
138 double m_dPoseOffsetZO;
139
140 // Data from NavBoard.
141
142 geoops::GPSCoordinate m_stCurrentGPSBasedPosition;
143
144 // Mats for storing frames and measures.
145
146 sl::Mat m_slFrame;
147 sl::Mat m_slDepthImage;
148 sl::Mat m_slDepthMeasure;
149 sl::Mat m_slPointCloud;
150
151 // Queues and mutexes for scheduling and copying camera frames and data to other threads.
152
153 std::queue<containers::FrameFetchContainer<cv::cuda::GpuMat>> m_qGPUFrameCopySchedule;
154 std::queue<containers::DataFetchContainer<std::vector<ZedObjectData>>> m_qCustomBoxIngestSchedule;
155 std::queue<containers::DataFetchContainer<Pose>> m_qPoseCopySchedule;
156 std::queue<containers::DataFetchContainer<sl::GeoPose>> m_qGeoPoseCopySchedule;
157 std::queue<containers::DataFetchContainer<sl::Plane>> m_qFloorCopySchedule;
158 std::queue<containers::DataFetchContainer<sl::SensorsData>> m_qSensorsCopySchedule;
159 std::queue<containers::DataFetchContainer<std::vector<sl::ObjectData>>> m_qObjectDataCopySchedule;
160 std::queue<containers::DataFetchContainer<std::vector<sl::ObjectsBatch>>> m_qObjectBatchedDataCopySchedule;
161
162 // Mutexes for copying frames from the ZEDSDK to the OpenCV Mats.
163
164 std::shared_mutex m_muCustomBoxIngestMutex;
165 std::shared_mutex m_muPoseCopyMutex;
166 std::shared_mutex m_muGeoPoseCopyMutex;
167 std::shared_mutex m_muFloorCopyMutex;
168 std::shared_mutex m_muSensorsCopyMutex;
169 std::shared_mutex m_muObjectDataCopyMutex;
170 std::shared_mutex m_muObjectBatchedDataCopyMutex;
171
172 // Atomic flags for checking if data is queued.
173
174 bool m_bQueueTogglesAlreadyReset;
175 std::atomic<bool> m_bNormalFramesQueued;
176 std::atomic<bool> m_bDepthFramesQueued;
177 std::atomic<bool> m_bPointCloudsQueued;
178 std::atomic<bool> m_bPosesQueued;
179 std::atomic<bool> m_bGeoPosesQueued;
180 std::atomic<bool> m_bFloorsQueued;
181 std::atomic<bool> m_bSensorsQueued;
182 std::atomic<bool> m_bObjectsQueued;
183 std::atomic<bool> m_bBatchedObjectsQueued;
184
186 // Declare private methods.
188
189 void ThreadedContinuousCode() override;
190 void PooledLinearCode() override;
191};
192#endif
This class implements and interfaces with the most common ZEDSDK cameras and features....
Definition ZEDCam.h:31
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 f...
Definition ZEDCam.cpp:1074
void DisableSpatialMapping() override
Disabled the spatial mapping feature of the camera.
Definition ZEDCam.cpp:2144
void DisablePositionalTracking() override
Disable to positional tracking functionality of the camera.
Definition ZEDCam.cpp:2010
sl::FUSION_ERROR_CODE SubscribeFusionToCameraUUID(sl::CameraIdentifier &slCameraUUID) override
Give a UUID for another ZEDCam, subscribe that camera to this camera's Fusion instance....
Definition ZEDCam.cpp:1696
~ZEDCam()
Destroy the Zed Cam:: Zed Cam object.
Definition ZEDCam.cpp:257
sl::ERROR_CODE TrackCustomBoxObjects(std::vector< ZedObjectData > &vCustomObjects) override
A vector containing CustomBoxObjectData objects. These objects simply store information about your de...
Definition ZEDCam.cpp:1619
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 dat...
Definition ZEDCam.cpp:1308
sl::ERROR_CODE RebootCamera() override
Performs a hardware reset of the ZED2 or ZED2i camera.
Definition ZEDCam.cpp:1678
void ThreadedContinuousCode() override
The code inside this private method runs in a separate thread, but still has access to this*....
Definition ZEDCam.cpp:289
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:1955
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 curr...
Definition ZEDCam.cpp:1775
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:2078
bool GetPositionalTrackingEnabled() override
Accessor for if the positional tracking functionality of the camera has been enabled and functioning.
Definition ZEDCam.cpp:2289
sl::ERROR_CODE EnableObjectDetection(const bool bEnableBatching=false) override
Enables the object detection and tracking feature of the camera.
Definition ZEDCam.cpp:2160
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....
Definition ZEDCam.cpp:1246
unsigned int GetCameraSerial() override
Accessor for the camera's serial number.
Definition ZEDCam.cpp:2273
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...
Definition ZEDCam.cpp:2357
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...
Definition ZEDCam.cpp:1460
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...
Definition ZEDCam.cpp:2054
sl::FusedPositionalTrackingStatus GetFusedPositionalTrackingState() override
Accessor for the current positional tracking status of the fusion instance.
Definition ZEDCam.cpp:2321
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...
Definition ZEDCam.cpp:1522
bool GetUsingGPUMem() const override
Accessor for if this ZED is storing it's frames in GPU memory.
Definition ZEDCam.cpp:2229
sl::SPATIAL_MAPPING_STATE GetSpatialMappingState() override
Accessor for the current state of the camera's spatial mapping feature.
Definition ZEDCam.cpp:2336
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 bu...
Definition ZEDCam.cpp:1165
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 ...
Definition ZEDCam.cpp:1001
sl::PositionalTrackingStatus GetPositionalTrackingState() override
Accessor for the current positional tracking status of the camera.
Definition ZEDCam.cpp:2305
bool GetCameraIsOpen() override
Accessor for the current status of the camera.
Definition ZEDCam.cpp:2213
sl::CameraIdentifier PublishCameraToFusion() override
Signal this camera to make its data available to the Fusion module and retrieve a UUID for this class...
Definition ZEDCam.cpp:1751
void PooledLinearCode() override
This method holds the code that is ran in the thread pool started by the ThreadedLinearCode() method....
Definition ZEDCam.cpp:713
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 in...
Definition ZEDCam.cpp:1368
void DisableObjectDetection() override
Disables the object detection and tracking feature of the camera.
Definition ZEDCam.cpp:2196
std::future< bool > RequestSensorsCopy(sl::SensorsData &slSensorsData) override
Requests the most up to date sensors data from the camera. This data include IMU pose and raw values,...
Definition ZEDCam.cpp:1426
bool GetObjectDetectionEnabled() override
Accessor for if the cameras object detection and tracking feature is enabled.
Definition ZEDCam.cpp:2424
sl::ERROR_CODE ResetPositionalTracking() override
Resets the cameras X,Y,Z translation and Roll,Pitch,Yaw orientation back to 0. THINK CAREFULLY!...
Definition ZEDCam.cpp:1579
std::string GetCameraModel() override
Accessor for the model enum from the ZEDSDK and represents the camera model as a string.
Definition ZEDCam.cpp:2244
This class serves as a middle inheritor between the Camera interface and the ZEDCam class....
Definition ZEDCamera.hpp:33
This struct is used within the ZEDCam class to store the camera pose with high precision....
Definition ZEDCamera.hpp:77
This struct stores/contains information about a GPS data.
Definition GeospatialOperations.hpp:100