14#include "../AutonomyLogging.h"
15#include "../util/GeospatialOperations.hpp"
19#include <sl/Camera.hpp>
20#include <sl/Fusion.hpp>
52 std::string szObjectUUID = sl::generate_unique_id().get();
61 bool bObjectRemainsOnFloorPlane =
false;
64 std::string GetObjectUUID() {
return szObjectUUID; };
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)
118 stTranslation.dX = dX;
119 stTranslation.dY = dY;
120 stTranslation.dZ = dZ;
121 stEulerAngles.dXO = dXO;
122 stEulerAngles.dYO = dYO;
123 stEulerAngles.dZO = dZO;
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) :
164 nPropFramesPerSecond,
168 bEnableRecordingFlag,
169 nNumFrameRetrievalThreads)
173 (void) bUseHalfDepthPrecision;
174 (void) bEnableFusionMaster;
175 m_bCameraIsFusionMaster = bEnableFusionMaster;
176 m_unCameraSerialNumber = unCameraSerialNumber;
214 std::promise<bool> pmPromise;
215 std::future<bool> fuFuture = pmPromise.get_future();
218 pmPromise.set_value(
false);
221 LOG_ERROR(logging::g_qSharedLogger,
"ZEDCamera::RequestFrameCopy(cv::cuda::GpuMat& cvGPUFrame) not implemented. If SIM_MODE use cv::Mat version instead.");
252 (void) bRetrieveMeasure;
253 std::promise<bool> pmPromise;
256 pmPromise.set_value(
false);
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 "
263 return pmPromise.get_future();
289 (void) cvGPUPointCloud;
290 std::promise<bool> pmPromise;
293 pmPromise.set_value(
false);
296 LOG_ERROR(logging::g_qSharedLogger,
297 "ZEDCamera::RequestPointCloudCopy(cv::cuda::GpuMat& cvGPUPointCloud) not implemented. If SIM_MODE use cv::Mat version instead.");
299 return pmPromise.get_future();
337 std::promise<bool> pmPromise;
340 pmPromise.set_value(
false);
343 LOG_ERROR(logging::g_qSharedLogger,
"ZEDCamera::RequestFloorPlaneCopy(sl::Plane& slFloorPlane) not implemented.");
345 return pmPromise.get_future();
360 (void) slSensorsData;
361 std::promise<bool> pmPromise;
364 pmPromise.set_value(
false);
367 LOG_ERROR(logging::g_qSharedLogger,
"ZEDCamera::RequestSensorsCopy(sl::SensorsData& slSensorsData) not implemented.");
369 return pmPromise.get_future();
385 std::promise<bool> pmPromise;
388 pmPromise.set_value(
false);
391 LOG_ERROR(logging::g_qSharedLogger,
"ZEDCamera::RequestObjectsCopy(std::vector<sl::ObjectData>& vObjectData) not implemented.");
393 return pmPromise.get_future();
408 (void) vBatchedObjectData;
409 std::promise<bool> pmPromise;
412 pmPromise.set_value(
false);
415 LOG_ERROR(logging::g_qSharedLogger,
"ZEDCamera::RequestBatchedObjectsCopy(std::vector<sl::ObjectsBatch>& vBatchedObjectData) not implemented.");
417 return pmPromise.get_future();
442 (void) vCustomObjects;
445 LOG_ERROR(logging::g_qSharedLogger,
"ZEDCamera::TrackCustomBoxObjects(const std::vector<ZedObjectData>& vCustomObjects) not implemented.");
447 return sl::ERROR_CODE::FAILURE;
493 (void) stNewGPSLocation;
496 LOG_ERROR(logging::g_qSharedLogger,
"ZEDCamera::IngestGPSDataToFusion(geoops::GPSCoordinate stNewGPSLocation) not implemented.");
498 return sl::FUSION_ERROR_CODE::FAILURE;
514 virtual sl::ERROR_CODE
EnablePositionalTracking(
const float fExpectedCameraHeightFromFloorTolerance = constants::ZED_DEFAULT_FLOOR_PLANE_ERROR) = 0;
538 virtual void SetPositionalPose(
const double dX,
const double dY,
const double dZ,
const double dXO,
const double dYO,
const double dZO) = 0;
551 LOG_ERROR(logging::g_qSharedLogger,
"ZEDCamera::EnableSpatialMapping() not implemented.");
553 return sl::ERROR_CODE::FAILURE;
566 LOG_ERROR(logging::g_qSharedLogger,
"ZEDCamera::DisableSpatialMapping() not implemented.");
581 (void) bEnableBatching;
584 LOG_ERROR(logging::g_qSharedLogger,
"ZEDCamera::EnableObjectDetection(const bool bEnableBatching = false) not implemented.");
586 return sl::ERROR_CODE::FAILURE;
599 LOG_ERROR(logging::g_qSharedLogger,
"ZEDCamera::DisableObjectDetection() not implemented.");
670 sl::PositionalTrackingStatus stStatus;
673 LOG_ERROR(logging::g_qSharedLogger,
"ZEDCamera::GetPositionalTrackingState() not implemented.");
689 sl::FusedPositionalTrackingStatus stStatus;
692 LOG_ERROR(logging::g_qSharedLogger,
"ZEDCamera::GetFusedPositionalTrackingState() not implemented.");
722 LOG_ERROR(logging::g_qSharedLogger,
"ZEDCamera::ExtractSpatialMapAsync(std::future<sl::Mesh>& fuMeshFuture) not implemented.");
724 return sl::SPATIAL_MAPPING_STATE::NOT_ENABLED;
743 const std::memory_order ATOMIC_MEMORY_ORDER_METHOD = std::memory_order_relaxed;
750 unsigned int m_unCameraSerialNumber;
751 bool m_bCameraIsFusionMaster;
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