Autonomy Software C++ 24.5.1
Welcome to the Autonomy Software repository of the Mars Rover Design Team (MRDT) at Missouri University of Science and Technology (Missouri S&T)! API reference contains the source code and other resources for the development of the autonomy software for our Mars rover. The Autonomy Software project aims to compete in the University Rover Challenge (URC) by demonstrating advanced autonomous capabilities and robust navigation algorithms.
Loading...
Searching...
No Matches
ZEDCamera.hpp
Go to the documentation of this file.
1
11#ifndef ZEDCAMERA_HPP
12#define ZEDCAMERA_HPP
13
14#include "../AutonomyLogging.h"
15#include "../util/GeospatialOperations.hpp"
16#include "Camera.hpp"
17
19#include <sl/Camera.hpp>
20#include <sl/Fusion.hpp>
21
23
24
32class ZEDCamera : public Camera<cv::Mat>
33{
34 public:
36 // Declare public structs that are specific to and used within this class.
38
39
49 {
50 private:
51 // Declare and define private struct member variables.
52 std::string szObjectUUID = sl::generate_unique_id().get(); // This will automatically generate a guaranteed unique id so the object is traceable.
53
54 public:
55 // Declare and define public struct member variables.
56 cv::Rect2d cvBoundingBox; // The bounding box of the object in the image.
57 int nClassNumber; // This info is passed through from your detection algorithm and will improve tracking be ensure the type of object remains the
58 float fConfidence; // This info is passed through from your detection algorithm and will help improve tracking by throwing out bad detections.
59 // Whether of not this object remains on the floor plane. This parameter can't be changed for a given object tracking ID, it's advised to set it by class
60 // to avoid issues.
61 bool bObjectRemainsOnFloorPlane = false;
62
63 // Declare and define public struct getters.
64 std::string GetObjectUUID() { return szObjectUUID; };
65 };
66
67
76 struct Pose
77 {
78 private:
79 // Declare struct for storing translation values.
81 {
82 public:
83 double dX; // Translation in ZED_MEASURE_UNITS on the x-axis.
84 double dY; // Translation in ZED_MEASURE_UNITS on the y-axis.
85 double dZ; // Translation in ZED_MEASURE_UNITS on the z-axis.
86 };
87
88 // Declare struct for storing rotation values.
90 {
91 public:
92 double dXO; // Rotation in degrees around the x-axis.
93 double dYO; // Rotation in degrees around the y-axis.
94 double dZO; // Rotation in degrees around the z-axis.
95 };
96
97 public:
98 // Declare struct public member variables.
99 Translation stTranslation;
100 EulerAngles stEulerAngles;
101
102
115 Pose(const double dX = 0.0, const double dY = 0.0, const double dZ = 0.0, const double dXO = 0.0, const double dYO = 0.0, const double dZO = 0.0)
116 {
117 // Initialize member variables.
118 stTranslation.dX = dX;
119 stTranslation.dY = dY;
120 stTranslation.dZ = dZ;
121 stEulerAngles.dXO = dXO;
122 stEulerAngles.dYO = dYO;
123 stEulerAngles.dZO = dZO;
124 }
125 };
126
128 // Declare public methods and member variables.
130
131
151 ZEDCamera(const int nPropResolutionX,
152 const int nPropResolutionY,
153 const int nPropFramesPerSecond,
154 const double dPropHorizontalFOV,
155 const double dPropVerticalFOV,
156 const bool bEnableRecordingFlag,
157 const bool bMemTypeGPU,
158 const bool bUseHalfDepthPrecision,
159 const bool bEnableFusionMaster,
160 const int nNumFrameRetrievalThreads,
161 const unsigned int unCameraSerialNumber) :
162 Camera(nPropResolutionX,
163 nPropResolutionY,
164 nPropFramesPerSecond,
165 PIXEL_FORMATS::eZED,
166 dPropHorizontalFOV,
167 dPropVerticalFOV,
168 bEnableRecordingFlag,
169 nNumFrameRetrievalThreads)
170 {
171 // Initialize member variables. Some parameters are not used.
172 (void) bMemTypeGPU;
173 (void) bUseHalfDepthPrecision;
174 (void) bEnableFusionMaster;
175 m_bCameraIsFusionMaster = bEnableFusionMaster;
176 m_unCameraSerialNumber = unCameraSerialNumber;
177 }
178
179
186 virtual ~ZEDCamera() = default;
187
188
199 std::future<bool> RequestFrameCopy(cv::Mat& cvFrame) override = 0;
200
201
210 virtual std::future<bool> RequestFrameCopy(cv::cuda::GpuMat& cvGPUFrame)
211 {
212 // Create instance variables.
213 (void) cvGPUFrame;
214 std::promise<bool> pmPromise;
215 std::future<bool> fuFuture = pmPromise.get_future();
216
217 // Immediately set the promise to false.
218 pmPromise.set_value(false);
219
220 // Submit logger message.
221 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::RequestFrameCopy(cv::cuda::GpuMat& cvGPUFrame) not implemented. If SIM_MODE use cv::Mat version instead.");
222
223 return fuFuture;
224 }
225
226
236 virtual std::future<bool> RequestDepthCopy(cv::Mat& cvDepth, const bool bRetrieveMeasure = true) = 0;
237
238
248 virtual std::future<bool> RequestDepthCopy(cv::cuda::GpuMat& cvGPUDepth, const bool bRetrieveMeasure = true)
249 {
250 // Initialize instance variables.
251 (void) cvGPUDepth;
252 (void) bRetrieveMeasure;
253 std::promise<bool> pmPromise;
254
255 // Immediately set the promise to false.
256 pmPromise.set_value(false);
257
258 // Submit logger message.
259 LOG_ERROR(logging::g_qSharedLogger,
260 "ZEDCamera::RequestDepthCopy(cv::cuda::GpuMat& cvGPUDepth, const bool bRetrieveMeasure = true) not implemented. If SIM_MODE use cv::Mat version "
261 "instead.");
262
263 return pmPromise.get_future();
264 }
265
266
275 virtual std::future<bool> RequestPointCloudCopy(cv::Mat& cvPointCloud) = 0;
276
277
286 virtual std::future<bool> RequestPointCloudCopy(cv::cuda::GpuMat& cvGPUPointCloud)
287 {
288 // Initialize instance variables.
289 (void) cvGPUPointCloud;
290 std::promise<bool> pmPromise;
291
292 // Immediately set the promise to false.
293 pmPromise.set_value(false);
294
295 // Submit logger message.
296 LOG_ERROR(logging::g_qSharedLogger,
297 "ZEDCamera::RequestPointCloudCopy(cv::cuda::GpuMat& cvGPUPointCloud) not implemented. If SIM_MODE use cv::Mat version instead.");
298
299 return pmPromise.get_future();
300 }
301
302
311 virtual std::future<bool> RequestPositionalPoseCopy(Pose& stPose) = 0;
312
313
322 virtual std::future<bool> RequestFusionGeoPoseCopy(sl::GeoPose& slGeoPose) = 0;
323
324
333 virtual std::future<bool> RequestFloorPlaneCopy(sl::Plane& slFloorPlane)
334 {
335 // Initialize instance variables.
336 (void) slFloorPlane;
337 std::promise<bool> pmPromise;
338
339 // Immediately set the promise to false.
340 pmPromise.set_value(false);
341
342 // Submit logger message.
343 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::RequestFloorPlaneCopy(sl::Plane& slFloorPlane) not implemented.");
344
345 return pmPromise.get_future();
346 }
347
348
357 virtual std::future<bool> RequestSensorsCopy(sl::SensorsData& slSensorsData)
358 {
359 // Initialize instance variables.
360 (void) slSensorsData;
361 std::promise<bool> pmPromise;
362
363 // Immediately set the promise to false.
364 pmPromise.set_value(false);
365
366 // Submit logger message.
367 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::RequestSensorsCopy(sl::SensorsData& slSensorsData) not implemented.");
368
369 return pmPromise.get_future();
370 }
371
372
381 virtual std::future<bool> RequestObjectsCopy(std::vector<sl::ObjectData>& vObjectData)
382 {
383 // Initialize instance variables.
384 (void) vObjectData;
385 std::promise<bool> pmPromise;
386
387 // Immediately set the promise to false.
388 pmPromise.set_value(false);
389
390 // Submit logger message.
391 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::RequestObjectsCopy(std::vector<sl::ObjectData>& vObjectData) not implemented.");
392
393 return pmPromise.get_future();
394 }
395
396
405 virtual std::future<bool> RequestBatchedObjectsCopy(std::vector<sl::ObjectsBatch>& vBatchedObjectData)
406 {
407 // Initialize instance variables.
408 (void) vBatchedObjectData;
409 std::promise<bool> pmPromise;
410
411 // Immediately set the promise to false.
412 pmPromise.set_value(false);
413
414 // Submit logger message.
415 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::RequestBatchedObjectsCopy(std::vector<sl::ObjectsBatch>& vBatchedObjectData) not implemented.");
416
417 return pmPromise.get_future();
418 }
419
420
428 virtual sl::ERROR_CODE ResetPositionalTracking() = 0;
429
430
439 virtual sl::ERROR_CODE TrackCustomBoxObjects(std::vector<ZedObjectData>& vCustomObjects)
440 {
441 // Initialize instance variables.
442 (void) vCustomObjects;
443
444 // Submit logger message.
445 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::TrackCustomBoxObjects(const std::vector<ZedObjectData>& vCustomObjects) not implemented.");
446
447 return sl::ERROR_CODE::FAILURE;
448 }
449
450
458 virtual sl::ERROR_CODE RebootCamera() = 0;
459
460
469 virtual sl::FUSION_ERROR_CODE SubscribeFusionToCameraUUID(sl::CameraIdentifier& slCameraUUID) = 0;
470
471
479 virtual sl::CameraIdentifier PublishCameraToFusion() = 0;
480
481
490 virtual sl::FUSION_ERROR_CODE IngestGPSDataToFusion(geoops::GPSCoordinate stNewGPSLocation)
491 {
492 // Initialize instance variables.
493 (void) stNewGPSLocation;
494
495 // Submit logger message.
496 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::IngestGPSDataToFusion(geoops::GPSCoordinate stNewGPSLocation) not implemented.");
497
498 return sl::FUSION_ERROR_CODE::FAILURE;
499 }
500
502 // Setters for class member variables.
504
505
514 virtual sl::ERROR_CODE EnablePositionalTracking(const float fExpectedCameraHeightFromFloorTolerance = constants::ZED_DEFAULT_FLOOR_PLANE_ERROR) = 0;
515
516
523 virtual void DisablePositionalTracking() = 0;
524
525
538 virtual void SetPositionalPose(const double dX, const double dY, const double dZ, const double dXO, const double dYO, const double dZO) = 0;
539
540
548 virtual sl::ERROR_CODE EnableSpatialMapping()
549 {
550 // Submit logger message.
551 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::EnableSpatialMapping() not implemented.");
552
553 return sl::ERROR_CODE::FAILURE;
554 }
555
556
564 {
565 // Submit logger message.
566 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::DisableSpatialMapping() not implemented.");
567 }
568
569
578 virtual sl::ERROR_CODE EnableObjectDetection(const bool bEnableBatching = false)
579 {
580 // Initialize instance variables.
581 (void) bEnableBatching;
582
583 // Submit logger message.
584 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::EnableObjectDetection(const bool bEnableBatching = false) not implemented.");
585
586 return sl::ERROR_CODE::FAILURE;
587 }
588
589
597 {
598 // Submit logger message.
599 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::DisableObjectDetection() not implemented.");
600 }
601
603 // Accessors for class member variables.
605
606
615 virtual bool GetUsingGPUMem() const { return false; }
616
617
626 virtual bool GetIsFusionMaster() const { return m_bCameraIsFusionMaster; }
627
628
636 virtual std::string GetCameraModel() = 0;
637
638
646 virtual unsigned int GetCameraSerial() { return m_unCameraSerialNumber; };
647
648
658
659
667 virtual sl::PositionalTrackingStatus GetPositionalTrackingState()
668 {
669 // Initialize instance variable.
670 sl::PositionalTrackingStatus stStatus;
671
672 // Submit logger message.
673 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::GetPositionalTrackingState() not implemented.");
674
675 return stStatus;
676 }
677
678
686 virtual sl::FusedPositionalTrackingStatus GetFusedPositionalTrackingState()
687 {
688 // Initialize instance variable.
689 sl::FusedPositionalTrackingStatus stStatus;
690
691 // Submit logger message.
692 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::GetFusedPositionalTrackingState() not implemented.");
693
694 return stStatus;
695 }
696
697
705 virtual sl::SPATIAL_MAPPING_STATE GetSpatialMappingState() { return sl::SPATIAL_MAPPING_STATE::NOT_ENABLED; }
706
707
716 virtual sl::SPATIAL_MAPPING_STATE ExtractSpatialMapAsync(std::future<sl::Mesh>& fuMeshFuture)
717 {
718 // Initialize instance variables.
719 (void) fuMeshFuture;
720
721 // Submit logger message.
722 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::ExtractSpatialMapAsync(std::future<sl::Mesh>& fuMeshFuture) not implemented.");
723
724 return sl::SPATIAL_MAPPING_STATE::NOT_ENABLED;
725 }
726
727
736 virtual bool GetObjectDetectionEnabled() { return false; }
737
738 protected:
740 // Declare class constants.
742
743 const std::memory_order ATOMIC_MEMORY_ORDER_METHOD = std::memory_order_relaxed;
744
746 // Declare protected member variables.
748
749 // ZED Camera specific.
750 unsigned int m_unCameraSerialNumber;
751 bool m_bCameraIsFusionMaster;
752
753 private:
755 // Declare private member variables.
757};
758
759#endif
Defines the Camera base interface class.
This interface class serves as a base for all other classes that will implement and interface with a ...
Definition Camera.hpp:34
This class serves as a middle inheritor between the Camera interface and the ZEDCam class....
Definition ZEDCamera.hpp:33
virtual sl::SPATIAL_MAPPING_STATE ExtractSpatialMapAsync(std::future< sl::Mesh > &fuMeshFuture)
Puts a Mesh pointer into a queue so a copy of a spatial mapping mesh from the camera can be written t...
Definition ZEDCamera.hpp:716
virtual unsigned int GetCameraSerial()
Accessor for the Camera Serial private member.
Definition ZEDCamera.hpp:646
virtual sl::ERROR_CODE RebootCamera()=0
Reboots the camera.
virtual std::future< bool > RequestBatchedObjectsCopy(std::vector< sl::ObjectsBatch > &vBatchedObjectData)
Puts a vector of ObjectsBatch pointers into a queue so a copy of a vector of ObjectsBatch from the ca...
Definition ZEDCamera.hpp:405
virtual sl::CameraIdentifier PublishCameraToFusion()=0
Publishes the camera to the fusion object.
virtual std::future< bool > RequestObjectsCopy(std::vector< sl::ObjectData > &vObjectData)
Puts a vector of ObjectData pointers into a queue so a copy of a vector of ObjectData from the camera...
Definition ZEDCamera.hpp:381
virtual bool GetIsFusionMaster() const
Accessor for if this ZED is running a fusion instance.
Definition ZEDCamera.hpp:626
virtual void DisablePositionalTracking()=0
Disables the position tracking of the camera.
virtual sl::FUSION_ERROR_CODE SubscribeFusionToCameraUUID(sl::CameraIdentifier &slCameraUUID)=0
Subscribes the fusion object to the camera with the given UUID.
virtual std::future< bool > RequestDepthCopy(cv::Mat &cvDepth, const bool bRetrieveMeasure=true)=0
Puts a frame pointer into a queue so a copy of a depth frame from the camera can be written to it.
virtual void DisableSpatialMapping()
Disables spatial mapping.
Definition ZEDCamera.hpp:563
virtual std::future< bool > RequestFloorPlaneCopy(sl::Plane &slFloorPlane)
Puts a FloorPlane pointer into a queue so a copy of a FloorPlane from the camera can be written to it...
Definition ZEDCamera.hpp:333
virtual ~ZEDCamera()=default
Destroy the ZEDCamera object.
virtual sl::PositionalTrackingStatus GetPositionalTrackingState()
Accessor for the Positional Tracking State private member.
Definition ZEDCamera.hpp:667
virtual sl::ERROR_CODE EnableObjectDetection(const bool bEnableBatching=false)
Enables object detection.
Definition ZEDCamera.hpp:578
virtual sl::ERROR_CODE EnableSpatialMapping()
Enables spatial mapping.
Definition ZEDCamera.hpp:548
virtual sl::FUSION_ERROR_CODE IngestGPSDataToFusion(geoops::GPSCoordinate stNewGPSLocation)
Ingests GPS data into the fusion object.
Definition ZEDCamera.hpp:490
virtual void SetPositionalPose(const double dX, const double dY, const double dZ, const double dXO, const double dYO, const double dZO)=0
Mutator for the Positional Pose private member.
virtual std::future< bool > RequestDepthCopy(cv::cuda::GpuMat &cvGPUDepth, const bool bRetrieveMeasure=true)
Puts a frame pointer into a queue so a copy of a depth frame from the camera can be written to it.
Definition ZEDCamera.hpp:248
virtual bool GetUsingGPUMem() const
Accessor for the Using G P U Memory private member.
Definition ZEDCamera.hpp:615
virtual sl::ERROR_CODE TrackCustomBoxObjects(std::vector< ZedObjectData > &vCustomObjects)
Tracks custom bounding boxes in the camera's field of view.
Definition ZEDCamera.hpp:439
virtual std::future< bool > RequestFusionGeoPoseCopy(sl::GeoPose &slGeoPose)=0
Puts a GeoPose pointer into a queue so a copy of a GeoPose from the camera can be written to it.
virtual sl::ERROR_CODE ResetPositionalTracking()=0
Resets the positional tracking of the camera.
virtual std::string GetCameraModel()=0
Accessor for the Camera Model private member.
virtual bool GetPositionalTrackingEnabled()=0
Accessor for the Positional Tracking Enabled private member.
virtual sl::ERROR_CODE EnablePositionalTracking(const float fExpectedCameraHeightFromFloorTolerance=constants::ZED_DEFAULT_FLOOR_PLANE_ERROR)=0
Enables the position tracking of the camera.
virtual std::future< bool > RequestFrameCopy(cv::cuda::GpuMat &cvGPUFrame)
Puts a frame pointer into a queue so a copy of a frame from the camera can be written to it.
Definition ZEDCamera.hpp:210
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.
Definition ZEDCamera.hpp:151
virtual std::future< bool > RequestPositionalPoseCopy(Pose &stPose)=0
Puts a Pose pointer into a queue so a copy of a Pose from the camera can be written to it.
virtual std::future< bool > RequestPointCloudCopy(cv::Mat &cvPointCloud)=0
Puts a frame pointer into a queue so a copy of a point cloud from the camera can be written to it.
virtual std::future< bool > RequestPointCloudCopy(cv::cuda::GpuMat &cvGPUPointCloud)
Puts a frame pointer into a queue so a copy of a point cloud from the camera can be written to it.
Definition ZEDCamera.hpp:286
virtual std::future< bool > RequestSensorsCopy(sl::SensorsData &slSensorsData)
Puts a SensorsData pointer into a queue so a copy of a SensorsData from the camera can be written to ...
Definition ZEDCamera.hpp:357
virtual void DisableObjectDetection()
Disables object detection.
Definition ZEDCamera.hpp:596
virtual bool GetObjectDetectionEnabled()
Accessor for the Object Detection Enabled private member.
Definition ZEDCamera.hpp:736
std::future< bool > RequestFrameCopy(cv::Mat &cvFrame) override=0
virtual sl::FusedPositionalTrackingStatus GetFusedPositionalTrackingState()
Accessor for the Fused Positional Tracking State private member.
Definition ZEDCamera.hpp:686
virtual sl::SPATIAL_MAPPING_STATE GetSpatialMappingState()
Accessor for the Spatial Mapping State private member.
Definition ZEDCamera.hpp:705
Definition ZEDCamera.hpp:90
Definition ZEDCamera.hpp:81
This struct is used within the ZEDCam class to store the camera pose with high precision....
Definition ZEDCamera.hpp:77
Pose(const double dX=0.0, const double dY=0.0, const double dZ=0.0, const double dXO=0.0, const double dYO=0.0, const double dZO=0.0)
Construct a new Pose object.
Definition ZEDCamera.hpp:115
This struct is part of the ZEDCam class and is used as a container for all bounding box data that is ...
Definition ZEDCamera.hpp:49
This struct stores/contains information about a GPS data.
Definition GeospatialOperations.hpp:99