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
310 virtual sl::ERROR_CODE ResetPositionalTracking() = 0;
311
312
321 virtual sl::ERROR_CODE TrackCustomBoxObjects(std::vector<ZedObjectData>& vCustomObjects)
322 {
323 // Initialize instance variables.
324 (void) vCustomObjects;
325
326 // Submit logger message.
327 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::TrackCustomBoxObjects(const std::vector<ZedObjectData>& vCustomObjects) not implemented.");
328
329 return sl::ERROR_CODE::FAILURE;
330 }
331
332
340 virtual sl::ERROR_CODE RebootCamera() = 0;
341
342
351 virtual sl::FUSION_ERROR_CODE SubscribeFusionToCameraUUID(sl::CameraIdentifier& slCameraUUID) = 0;
352
353
361 virtual sl::CameraIdentifier PublishCameraToFusion() = 0;
362
363
372 virtual sl::FUSION_ERROR_CODE IngestGPSDataToFusion(geoops::GPSCoordinate stNewGPSLocation)
373 {
374 // Initialize instance variables.
375 (void) stNewGPSLocation;
376
377 // Submit logger message.
378 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::IngestGPSDataToFusion(geoops::GPSCoordinate stNewGPSLocation) not implemented.");
379
380 return sl::FUSION_ERROR_CODE::FAILURE;
381 }
382
384 // Setters for class member variables.
386
387
396 virtual sl::ERROR_CODE EnablePositionalTracking(const float fExpectedCameraHeightFromFloorTolerance = constants::ZED_DEFAULT_FLOOR_PLANE_ERROR) = 0;
397
398
405 virtual void DisablePositionalTracking() = 0;
406
407
420 virtual void SetPositionalPose(const double dX, const double dY, const double dZ, const double dXO, const double dYO, const double dZO) = 0;
421
422
430 virtual sl::ERROR_CODE EnableSpatialMapping()
431 {
432 // Submit logger message.
433 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::EnableSpatialMapping() not implemented.");
434
435 return sl::ERROR_CODE::FAILURE;
436 }
437
438
446 {
447 // Submit logger message.
448 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::DisableSpatialMapping() not implemented.");
449 }
450
451
460 virtual sl::ERROR_CODE EnableObjectDetection(const bool bEnableBatching = false)
461 {
462 // Initialize instance variables.
463 (void) bEnableBatching;
464
465 // Submit logger message.
466 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::EnableObjectDetection(const bool bEnableBatching = false) not implemented.");
467
468 return sl::ERROR_CODE::FAILURE;
469 }
470
471
479 {
480 // Submit logger message.
481 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::DisableObjectDetection() not implemented.");
482 }
483
485 // Accessors for class member variables.
487
488
497 virtual bool GetUsingGPUMem() const { return false; }
498
499
508 virtual bool GetIsFusionMaster() const { return m_bCameraIsFusionMaster; }
509
510
518 virtual std::string GetCameraModel() = 0;
519
520
528 virtual unsigned int GetCameraSerial() { return m_unCameraSerialNumber; };
529
530
539 virtual std::future<bool> RequestPositionalPoseCopy(Pose& stPose) = 0;
540
541
550 virtual std::future<bool> RequestFusionGeoPoseCopy(sl::GeoPose& slGeoPose) = 0;
551
552
561 virtual std::future<bool> RequestFloorPlaneCopy(sl::Plane& slFloorPlane)
562 {
563 // Initialize instance variables.
564 (void) slFloorPlane;
565 std::promise<bool> pmPromise;
566
567 // Immediately set the promise to false.
568 pmPromise.set_value(false);
569
570 // Submit logger message.
571 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::RequestFloorPlaneCopy(sl::Plane& slFloorPlane) not implemented.");
572
573 return pmPromise.get_future();
574 }
575
576
586
587
595 virtual sl::PositionalTrackingStatus GetPositionalTrackingState()
596 {
597 // Initialize instance variable.
598 sl::PositionalTrackingStatus stStatus;
599
600 // Submit logger message.
601 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::GetPositionalTrackingState() not implemented.");
602
603 return stStatus;
604 }
605
606
614 virtual sl::FusedPositionalTrackingStatus GetFusedPositionalTrackingState()
615 {
616 // Initialize instance variable.
617 sl::FusedPositionalTrackingStatus stStatus;
618
619 // Submit logger message.
620 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::GetFusedPositionalTrackingState() not implemented.");
621
622 return stStatus;
623 }
624
625
633 virtual sl::SPATIAL_MAPPING_STATE GetSpatialMappingState() { return sl::SPATIAL_MAPPING_STATE::NOT_ENABLED; }
634
635
644 virtual sl::SPATIAL_MAPPING_STATE ExtractSpatialMapAsync(std::future<sl::Mesh>& fuMeshFuture)
645 {
646 // Initialize instance variables.
647 (void) fuMeshFuture;
648
649 // Submit logger message.
650 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::ExtractSpatialMapAsync(std::future<sl::Mesh>& fuMeshFuture) not implemented.");
651
652 return sl::SPATIAL_MAPPING_STATE::NOT_ENABLED;
653 }
654
655
664 virtual bool GetObjectDetectionEnabled() { return false; }
665
666
675 virtual std::future<bool> RequestObjectsCopy(std::vector<sl::ObjectData>& vObjectData)
676 {
677 // Initialize instance variables.
678 (void) vObjectData;
679 std::promise<bool> pmPromise;
680
681 // Immediately set the promise to false.
682 pmPromise.set_value(false);
683
684 // Submit logger message.
685 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::RequestObjectsCopy(std::vector<sl::ObjectData>& vObjectData) not implemented.");
686
687 return pmPromise.get_future();
688 }
689
690
699 virtual std::future<bool> RequestBatchedObjectsCopy(std::vector<sl::ObjectsBatch>& vBatchedObjectData)
700 {
701 // Initialize instance variables.
702 (void) vBatchedObjectData;
703 std::promise<bool> pmPromise;
704
705 // Immediately set the promise to false.
706 pmPromise.set_value(false);
707
708 // Submit logger message.
709 LOG_ERROR(logging::g_qSharedLogger, "ZEDCamera::RequestBatchedObjectsCopy(std::vector<sl::ObjectsBatch>& vBatchedObjectData) not implemented.");
710
711 return pmPromise.get_future();
712 }
713
714 protected:
716 // Declare class constants.
718
719 const std::memory_order ATOMIC_MEMORY_ORDER_METHOD = std::memory_order_relaxed;
720
722 // Declare protected member variables.
724
725 // ZED Camera specific.
726 unsigned int m_unCameraSerialNumber;
727 bool m_bCameraIsFusionMaster;
728
729 private:
731 // Declare private member variables.
733};
734
735#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:644
virtual unsigned int GetCameraSerial()
Accessor for the Camera Serial private member.
Definition ZEDCamera.hpp:528
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:699
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:675
virtual bool GetIsFusionMaster() const
Accessor for if this ZED is running a fusion instance.
Definition ZEDCamera.hpp:508
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:445
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:561
virtual ~ZEDCamera()=default
Destroy the ZEDCamera object.
virtual sl::PositionalTrackingStatus GetPositionalTrackingState()
Accessor for the Positional Tracking State private member.
Definition ZEDCamera.hpp:595
virtual sl::ERROR_CODE EnableObjectDetection(const bool bEnableBatching=false)
Enables object detection.
Definition ZEDCamera.hpp:460
virtual sl::ERROR_CODE EnableSpatialMapping()
Enables spatial mapping.
Definition ZEDCamera.hpp:430
virtual sl::FUSION_ERROR_CODE IngestGPSDataToFusion(geoops::GPSCoordinate stNewGPSLocation)
Ingests GPS data into the fusion object.
Definition ZEDCamera.hpp:372
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:497
virtual sl::ERROR_CODE TrackCustomBoxObjects(std::vector< ZedObjectData > &vCustomObjects)
Tracks custom bounding boxes in the camera's field of view.
Definition ZEDCamera.hpp:321
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 void DisableObjectDetection()
Disables object detection.
Definition ZEDCamera.hpp:478
virtual bool GetObjectDetectionEnabled()
Accessor for the Object Detection Enabled private member.
Definition ZEDCamera.hpp:664
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:614
virtual sl::SPATIAL_MAPPING_STATE GetSpatialMappingState()
Accessor for the Spatial Mapping State private member.
Definition ZEDCamera.hpp:633
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