Camera Class Reference

This class serves as the primary interface between the camera and the various features provided by the SDK. More...

Functions

float GetRequestedCameraFPS ()
 Desired FPS from the ZED camera. More...
 
 Camera (int id)
 Default constructor. More...
 
ERROR_CODE Open (ref InitParameters initParameters)
 Opens the ZED camera from the provided InitParameters. More...
 
void Close ()
 Closes the camera. More...
 
sl.ERROR_CODE Grab (ref sl.RuntimeParameters runtimeParameters)
 This method will grab the latest images from the camera, rectify them, and compute the measurements based on the RuntimeParameters provided (depth, point cloud, tracking, etc.). More...
 
ERROR_CODE StartPublishing (ref CommunicationParameters commParams)
 Set this camera as a data provider for the Fusion module. More...
 
ERROR_CODE StopPublishing ()
 Set this camera as normal camera(without data providing). More...
 
sl.INPUT_TYPE GetInputType ()
 Return the sl.INPUT_TYPE currently used. More...
 
CalibrationParameters GetCalibrationParameters (bool raw=false)
 Return the calibration parameters of the camera. More...
 
sl.MODEL GetCameraModel ()
 Gets the camera model (sl.MODEL). More...
 
int GetCameraFirmwareVersion ()
 Gets the camera firmware version. More...
 
int GetSensorsFirmwareVersion ()
 Gets the sensors firmware version. More...
 
int GetZEDSerialNumber ()
 Gets the camera's serial number. More...
 
float GetFOV ()
 Returns the camera's vertical field of view in radians. More...
 
void UpdateSelfCalibration ()
 Perform a new self calibration process. More...
 
uint GetFrameDroppedCount ()
 Gets the number of frames dropped since Grab() was called for the first time. More...
 
sl.ERROR_CODE SaveCurrentImageInFile (sl.VIEW view, String filename)
 Save current image (specified by view) in a file defined by filename. More...
 
sl.ERROR_CODE SaveCurrentDepthInFile (SIDE side, String filename)
 Save the current depth in a file defined by filename. More...
 
sl.ERROR_CODE SaveCurrentPointCloudInFile (SIDE side, String filename)
 Save the current point cloud in a file defined by filename. More...
 
Depth Sensing
sl.ERROR_CODE RetrieveMeasure (sl.Mat mat, sl.MEASURE measure, sl.MEM mem=sl.MEM.CPU, sl.Resolution resolution=new sl.Resolution())
 Retrieves a measure texture from the ZED SDK and loads it into a sl.Mat. More...
 
int GetConfidenceThreshold ()
 Gets the current confidence threshold value for the disparity map (and by extension the depth map). More...
 
float GetDepthMinRangeValue ()
 Gets the closest measurable distance by the camera, according to the camera type and depth map parameters. More...
 
sl.ERROR_CODE GetCurrentMixMaxDepth (ref float min, ref float max)
 Gets the current range of perceived depth. More...
 
float GetDepthMaxRangeValue ()
 Returns the current maximum distance of depth/disparity estimation. More...
 
sl.ERROR_CODE EnablePositionalTracking (ref PositionalTrackingParameters positionalTrackingParameters)
 Initializes and starts the positional tracking processes. More...
 
void DisablePositionalTracking (string path="")
 Disables the positional tracking. More...
 
bool IsPositionalTrackingEnabled ()
 Tells if the tracking module is enabled. More...
 
ERROR_CODE SaveAreaMap (string areaFilePath)
 Saves the current area learning file. More...
 
AREA_EXPORT_STATE GetAreaExportState ()
 Returns the state of the spatial memory export process. More...
 
sl.ERROR_CODE ResetPositionalTracking (Quaternion rotation, Vector3 translation)
 Resets the tracking, and re-initializes the position with the given translation vector and rotation quaternion. More...
 
SensorsConfiguration GetSensorsConfiguration ()
 Returns the sensor configuration of the camera. More...
 
CameraInformation GetCameraInformation (Resolution resolution=new Resolution())
 Returns the CameraInformation associated the camera being used. More...
 
POSITIONAL_TRACKING_STATE GetPosition (ref Quaternion rotation, ref Vector3 position, REFERENCE_FRAME referenceType=REFERENCE_FRAME.WORLD)
 Gets the position of the camera and the current state of the camera Tracking. More...
 
PositionalTrackingStatus GetPositionalTrackingStatus ()
 Returns the current status of positional tracking module. More...
 
POSITIONAL_TRACKING_STATE GetPosition (ref Quaternion rotation, ref Vector3 translation, ref Quaternion targetQuaternion, ref Vector3 targetTranslation, REFERENCE_FRAME referenceFrame=REFERENCE_FRAME.WORLD)
 Gets the current position of the camera and state of the tracking, with an optional offset to the tracking frame. More...
 
POSITIONAL_TRACKING_STATE GetPosition (ref Quaternion rotation, ref Vector3 translation, TRACKING_FRAME trackingFrame, REFERENCE_FRAME referenceFrame=REFERENCE_FRAME.WORLD)
 Gets the current position of the camera and state of the tracking, with a defined tracking frame. More...
 
POSITIONAL_TRACKING_STATE GetPosition (ref Pose pose, REFERENCE_FRAME referenceType=REFERENCE_FRAME.WORLD)
 Gets the current position of the camera and state of the tracking, filling a Pose struct useful for AR pass-through. More...
 
ERROR_CODE SetIMUOrientationPrior (ref Quaternion rotation)
 Sets a prior to the IMU orientation (not for MODEL.ZED). More...
 
ERROR_CODE GetIMUOrientation (ref Quaternion rotation, TIME_REFERENCE referenceTime=TIME_REFERENCE.IMAGE)
 Gets the rotation given by the IMU. More...
 
ERROR_CODE GetSensorsData (ref SensorsData data, TIME_REFERENCE referenceTime=TIME_REFERENCE.IMAGE)
 Retrieves the SensorsData (IMU, magnetometer, barometer) at a specific time reference. More...
 
ERROR_CODE SetRegionOfInterest (sl.Mat roiMask, bool[] module)
 Defines a region of interest to focus on for all the SDK, discarding other parts. More...
 
ERROR_CODE GetRegionOfInterest (sl.Mat roiMask, sl.Resolution resolution=new sl.Resolution(), MODULE module=MODULE.ALL)
 Get the previously set or computed region of interest. More...
 
ERROR_CODE StartRegionOfInterestAutoDetection (RegionOfInterestParameters roiParams)
 Start the auto detection of a region of interest to focus on for all the SDK, discarding other parts. This detection is based on the general motion of the camera combined with the motion in the scene. The camera must move for this process, an internal motion detector is used, based on the Positional Tracking module. It requires a few hundreds frames of motion to compute the mask. More...
 
REGION_OF_INTEREST_AUTO_DETECTION_STATE GetRegionOfInterestAutoDetectionStatus ()
 Return the status of the automatic Region of Interest Detection. The automatic Region of Interest Detection is enabled by using StartRegionOfInterestAutoDetection More...
 
Recording
ERROR_CODE EnableRecording (string videoFileName, SVO_COMPRESSION_MODE compressionMode=SVO_COMPRESSION_MODE.H264_BASED, uint bitrate=0, int targetFPS=0, bool transcode=false)
 Creates an SVO file to be filled by EnableRecording() and DisableRecording(). More...
 
ERROR_CODE EnableRecording (RecordingParameters recordingParameters)
 Creates an SVO file to be filled by EnableRecording() and DisableRecording(). More...
 
sl.RecordingStatus GetRecordingStatus ()
 Get the recording information. More...
 
sl.RecordingParameters GetRecordingParameters ()
 Returns the RecordingParameters used. More...
 
void PauseRecording (bool status)
 Pauses or resumes the recording. More...
 
void DisableRecording ()
 Disables the recording initiated by EnableRecording() and closes the generated file. More...
 
ERROR_CODE IngestDataIntoSVO (ref SVOData data)
 Ingest SVOData in a SVO file. More...
 
ERROR_CODE RetrieveSVOData (string key, ref List< SVOData > data, ulong tsBegin, ulong tsEnd)
 Retrieves SVO data from the SVO file at the given channel key and in the given timestamp range. More...
 
List< string > GetSVODataKeys ()
 Gets the external channels that can be retrieved from the SVO file. More...
 
Streaming
ERROR_CODE EnableStreaming (STREAMING_CODEC codec=STREAMING_CODEC.H264_BASED, uint bitrate=8000, ushort port=30000, int gopSize=-1, bool adaptativeBitrate=false, int chunkSize=32768, int targetFPS=0)
 Creates an streaming pipeline. More...
 
ERROR_CODE EnableStreaming (ref StreamingParameters streamingParameters)
 Creates an streaming pipeline. More...
 
bool IsStreamingEnabled ()
 Tells if the streaming is running. More...
 
void DisableStreaming ()
 Disables the streaming initiated by EnableStreaming(). More...
 
sl.StreamingParameters GetStreamingParameters ()
 Returns the StreamingParameters used. More...
 

Static Functions

static void UnloadPlugin ()
 
static void UnloadInstance (int id)
 
static string GenerateUniqueID ()
 Generate a UUID like unique id to help identify and track AI detections. More...
 
static string GetSDKVersion ()
 Gets the version of the currently installed ZED SDK. More...
 
static sl.ERROR_CODE ConvertCoordinateSystem (ref Quaternion rotation, ref Vector3 translation, sl.COORDINATE_SYSTEM coordinateSystemSrc, sl.COORDINATE_SYSTEM coordinateSystemDest)
 Change the coordinate system of a transform matrix. More...
 
static void GetSDKVersion (ref int major, ref int minor, ref int patch)
 Gets the version of the currently installed ZED SDK. More...
 
static sl.DeviceProperties[] GetDeviceList (out int nbDevices)
 List all the connected devices with their associated information. More...
 
static sl.StreamingProperties[] GetStreamingDeviceList (out int nbDevices)
 List all the streaming devices with their associated information. More...
 
static sl.ERROR_CODE Reboot (int serialNumber, bool fullReboot=true)
 Performs a hardware reset of the ZED 2 and the ZED 2i. More...
 

Attributes

int CameraID = 0
 Camera ID (for multiple cameras) More...
 

Properties

int ImageWidth [get]
 Width of the images returned by the camera in pixels. More...
 
int ImageHeight [get]
 Height of the images returned by the camera in pixels. More...
 
float Baseline [get]
 Baseline of the camera (distance between the cameras). More...
 
float HorizontalFieldOfView [get]
 Current horizontal field of view in degrees of the camera. More...
 
float VerticalFieldOfView [get]
 Current vertical field of view in degrees of the camera. More...
 
SensorsConfiguration SensorsConfiguration [get]
 
CalibrationParameters CalibrationParametersRaw [get]
 Stereo parameters for current ZED camera prior to rectification (distorted). More...
 
CalibrationParameters CalibrationParametersRectified [get]
 Stereo parameters for current ZED camera after rectification (undistorted). More...
 
sl.MODEL CameraModel [get]
 Model of the camera. More...
 
bool IsCameraReady [get]
 Whether the camera has been successfully initialized. More...
 

Video

sl.ERROR_CODE RetrieveImage (sl.Mat mat, sl.VIEW view, sl.MEM mem=sl.MEM.CPU, sl.Resolution resolution=new sl.Resolution())
 Retrieves an image texture from the ZED SDK and loads it into a sl.Mat. More...
 
InitParameters GetInitParameters ()
 Returns the InitParameters associated with the Camera object. More...
 
RuntimeParameters GetRuntimeParameters ()
 Returns the RuntimeParameters used. More...
 
PositionalTrackingParameters GetPositionalTrackingParameters ()
 Returns the PositionalTrackingParameters used. More...
 
bool IsCameraSettingSupported (VIDEO_SETTINGS setting)
 Test if the video setting is supported by the camera. More...
 
void SetCameraSettings (VIDEO_SETTINGS settings, int minvalue, int maxvalue)
 Sets the min and max range values of the requested camera setting (used for settings with a range). More...
 
sl.ERROR_CODE GetCameraSettings (VIDEO_SETTINGS settings, ref int minvalue, ref int maxvalue)
 Returns the current range of the requested camera setting. More...
 
void SetCameraSettings (VIDEO_SETTINGS settings, int value)
 Sets the value of the requested camera setting (gain, brightness, hue, exposure, etc.). More...
 
int GetCameraSettings (VIDEO_SETTINGS settings)
 Returns the current value of the requested camera setting (gain, brightness, hue, exposure, etc.). More...
 
ERROR_CODE SetCameraSettings (VIDEO_SETTINGS settings, SIDE side, Rect roi, bool reset=false)
 Overloaded method for VIDEO_SETTINGS.AEC_AGC_ROI which takes a Rect as parameter. More...
 
ERROR_CODE GetCameraSettings (VIDEO_SETTINGS settings, SIDE side, ref Rect roi)
 Overloaded method for VIDEO_SETTINGS.AEC_AGC_ROI which takes a Rect as parameter. More...
 
void ResetCameraSettings ()
 Reset camera settings to default. More...
 
ulong GetCameraTimeStamp ()
 Gets the timestamp at the time the latest grabbed frame was extracted from the USB stream. More...
 
ulong GetCurrentTimeStamp ()
 Gets the current timestamp at the time the method is called. More...
 
int GetSVOPosition ()
 Returns the current playback position in the SVO file. More...
 
int GetSVOPositionAtTimestamp (ulong timestamp)
 Retrieves the frame index within the SVO file corresponding to the provided timestamp. More...
 
int GetSVONumberOfFrames ()
 Returns the number of frames in the SVO file. More...
 
void SetSVOPosition (int frame)
 Sets the position of the SVO file currently being read to a desired frame. More...
 
float GetCameraFPS ()
 Returns the current camera FPS. More...
 
bool IsOpened ()
 Reports if the camera has been successfully opened. More...
 
static sl.Resolution GetResolution (RESOLUTION resolution)
 Gets the corresponding sl.Resolution from an sl.RESOLUTION. More...
 

Spatial Mapping

sl.ERROR_CODE EnableSpatialMapping (ref SpatialMappingParameters spatialMappingParameters)
 Initializes and begins the spatial mapping processes. More...
 
sl.ERROR_CODE EnableSpatialMapping (SPATIAL_MAP_TYPE type=SPATIAL_MAP_TYPE.MESH, MAPPING_RESOLUTION mappingResolution=MAPPING_RESOLUTION.MEDIUM, MAPPING_RANGE mappingRange=MAPPING_RANGE.MEDIUM, bool saveTexture=false)
 Initializes and begins the spatial mapping processes. More...
 
SpatialMappingParameters GetSpatialMappingParameters ()
 Returns the SpatialMappingParameters used. More...
 
void DisableSpatialMapping ()
 Disables the spatial mapping process. More...
 
sl.ERROR_CODE UpdateMesh (int[] nbVerticesInSubmeshes, int[] nbTrianglesInSubmeshes, ref int nbUpdatedSubmesh, int[] updatedIndices, ref int nbVertices, ref int nbTriangles, int nbSubmeshMax)
 Updates the internal version of the mesh and returns the sizes of the meshes. More...
 
sl.ERROR_CODE UpdateMesh (ref Mesh mesh)
 Updates the internal version of the mesh and returns the sizes of the meshes. More...
 
sl.ERROR_CODE RetrieveMesh (Vector3[] vertices, int[] triangles, byte[] colors, int nbSubmeshMax, Vector2[] uvs, IntPtr textures)
 Retrieves all chunks of the current generated mesh. More...
 
sl.ERROR_CODE RetrieveMesh (ref Mesh mesh)
 Retrieves all chunks of the current generated mesh. More...
 
sl.ERROR_CODE RetrieveChunks (ref Mesh mesh)
 Retrieve all chunks of the generated mesh. More...
 
sl.ERROR_CODE RetrieveSpatialMap (ref Mesh mesh)
 Retrieves the current generated mesh. More...
 
sl.ERROR_CODE RetrieveSpatialMap (ref FusedPointCloud fusedPointCloud)
 Retrieves the current fused point cloud. More...
 
sl.ERROR_CODE UpdateFusedPointCloud (ref int nbVertices)
 Updates the fused point cloud (if spatial map type was FUSED_POINT_CLOUD). More...
 
sl.ERROR_CODE RetrieveFusedPointCloud (Vector4[] vertices)
 Retrieves all points of the fused point cloud. More...
 
ERROR_CODE ExtractWholeSpatialMap ()
 Extracts the current spatial map from the spatial mapping process. More...
 
void RequestSpatialMap ()
 Starts the mesh generation process in a thread that does not block the spatial mapping process. More...
 
void PauseSpatialMapping (bool status)
 Pauses or resumes the spatial mapping processes. More...
 
sl.ERROR_CODE GetMeshRequestStatus ()
 Returns the mesh generation status. More...
 
bool SaveMesh (string filename, MESH_FILE_FORMAT format)
 Saves the scanned mesh in a specific file format. More...
 
bool SavePointCloud (string filename, MESH_FILE_FORMAT format)
 Saves the scanned point cloud in a specific file format. More...
 
bool LoadMesh (string filename, int[] nbVerticesInSubmeshes, int[] nbTrianglesInSubmeshes, ref int nbSubmeshes, int[] updatedIndices, ref int nbVertices, ref int nbTriangles, int nbSubmeshMax, int[] textureSize=null)
 Loads a saved mesh file. More...
 
bool FilterMesh (MESH_FILTER filterParameters, int[] nbVerticesInSubmeshes, int[] nbTrianglesInSubmeshes, ref int nbSubmeshes, int[] updatedIndices, ref int nbVertices, ref int nbTriangles, int nbSubmeshMax)
 Filters a mesh to remove triangles while still preserving its overall shape (though less accurate). More...
 
bool FilterMesh (MESH_FILTER filterParameters, ref Mesh mesh)
 Filters a mesh to remove triangles while still preserving its overall shape (though less accurate). More...
 
bool ApplyTexture (int[] nbVerticesInSubmeshes, int[] nbTrianglesInSubmeshes, ref int nbSubmeshes, int[] updatedIndices, ref int nbVertices, ref int nbTriangles, int[] textureSize, int nbSubmeshMax)
 Applies the scanned texture onto the internal scanned mesh. More...
 
bool ApplyTexture (ref Mesh mesh)
 Applies the texture on a mesh. More...
 
SPATIAL_MAPPING_STATE GetSpatialMappingState ()
 Returns the current spatial mapping state. More...
 
Vector3 GetGravityEstimate ()
 Gets a vector pointing toward the direction of gravity. More...
 
void MergeChunks (int numberFaces, int[] nbVerticesInSubmeshes, int[] nbTrianglesInSubmeshes, ref int nbSubmeshes, int[] updatedIndices, ref int nbVertices, ref int nbTriangles, int nbSubmesh)
 Consolidates the chunks from a scan. More...
 

Plane Detection

sl.ERROR_CODE findFloorPlane (ref PlaneData plane, out float playerHeight, Quaternion priorQuat, Vector3 priorTrans)
 Detect the floor plane of the scene. More...
 
sl.ERROR_CODE FindFloorPlane (ref PlaneData plane, out float playerHeight, Quaternion priorQuat, Vector3 priorTrans)
 Detect the floor plane of the scene. More...
 
int convertFloorPlaneToMesh (Vector3[] vertices, int[] triangles, out int numVertices, out int numTriangles)
 Using data from a detected floor plane, updates supplied vertex and triangle arrays with data needed to make a mesh that represents it. More...
 
int ConvertFloorPlaneToMesh (Vector3[] vertices, int[] triangles, out int numVertices, out int numTriangles)
 Using data from a detected floor plane, updates supplied vertex and triangle arrays with data needed to make a mesh that represents it. More...
 
sl.ERROR_CODE findPlaneAtHit (ref PlaneData plane, Vector2 coord, ref PlaneDetectionParameters planeDetectionParameters)
 Checks the plane at the given left image coordinates. More...
 
sl.ERROR_CODE FindPlaneAtHit (ref PlaneData plane, Vector2 coord, ref PlaneDetectionParameters planeDetectionParameters)
 Checks the plane at the given left image coordinates. More...
 
int convertHitPlaneToMesh (Vector3[] vertices, int[] triangles, out int numVertices, out int numTriangles)
 Using data from a detected hit plane, updates supplied vertex and triangle arrays with data needed to make a mesh that represents it. More...
 
int ConvertHitPlaneToMesh (Vector3[] vertices, int[] triangles, out int numVertices, out int numTriangles)
 Using data from a detected hit plane, updates supplied vertex and triangle arrays with data needed to make a mesh that represents it. More...
 
static float ConvertRangePreset (MAPPING_RANGE rangePreset)
 Updates the range to match the specified preset. More...
 
static float ConvertResolutionPreset (MAPPING_RESOLUTION resolutionPreset)
 Updates the resolution to match the specified preset. More...
 

Object Detection

sl.ERROR_CODE EnableObjectDetection (ref ObjectDetectionParameters od_params)
 Initializes and starts object detection module. More...
 
sl.ERROR_CODE EnableBodyTracking (ref BodyTrackingParameters bt_params)
 Initializes and starts body tracking module. More...
 
void DisableObjectDetection (uint instanceID=0, bool disableAllInstance=false)
 Disable object detection module and release the resources. More...
 
void DisableBodyTracking (uint instanceID=0, bool disableAllInstance=false)
 Disable body tracking module and release the resources. More...
 
sl.ObjectDetectionParameters GetObjectDetectionParameters ()
 Returns the ObjectDetectionParameters used. More...
 
sl.BodyTrackingParameters GetBodyTrackingParameters ()
 Returns the BodyTrackingParameters used. More...
 
sl.ERROR_CODE IngestCustomBoxObjects (List< CustomBoxObjectData > objects_in)
 Feed the 3D Object tracking method with your own 2D bounding boxes from your own detection algorithm. More...
 
sl.ERROR_CODE RetrieveObjects (ref Objects objs, ref ObjectDetectionRuntimeParameters od_params, uint instanceID=0)
 Retrieve objects detected by the object detection module. More...
 
sl.ERROR_CODE RetrieveBodies (ref Bodies objs, ref BodyTrackingRuntimeParameters bt_params, uint instanceID=0)
 Retrieve bodies detected by the body tracking module. More...
 
sl.ERROR_CODE UpdateObjectsBatch (out int nbBatches)
 Update the batch trajectories and retrieve the number of batches. More...
 
sl.ERROR_CODE GetObjectsBatch (int batch_index, ref ObjectsBatch objectsBatch)
 Retrieve a batch of objects. More...
 
static AI_Model_status CheckAIModelStatus (AI_MODELS model, int gpu_id=0)
 Check if a corresponding optimized engine is found for the requested model based on your rig configuration. More...
 
static sl.ERROR_CODE OptimizeAIModel (AI_MODELS model, int gpu_id=0)
 Optimize the requested model, possible download if the model is not present on the host. More...
 

Detailed Description

This class serves as the primary interface between the camera and the various features provided by the SDK.

It enables seamless integration and access to a wide array of capabilities, including video streaming, depth sensing, object tracking, mapping, and much more.

Constructor and Destructor

◆ Camera()

Camera ( int  id)
inline

Default constructor.

Creates an empty Camera object.

Parameters
id

Functions

◆ GetRequestedCameraFPS()

float GetRequestedCameraFPS ( )
inline

Desired FPS from the ZED camera.

This is the maximum FPS for the camera's current resolution unless a lower setting was specified in Open().
Maximum values are bound by the camera's output, not system performance.

◆ UnloadPlugin()

static void UnloadPlugin ( )
inlinestatic

◆ UnloadInstance()

static void UnloadInstance ( int  id)
inlinestatic

◆ GenerateUniqueID()

static string GenerateUniqueID ( )
inlinestatic

Generate a UUID like unique id to help identify and track AI detections.

Returns
A UUID like unique id.

◆ Open()

ERROR_CODE Open ( ref InitParameters  initParameters)
inline

Opens the ZED camera from the provided InitParameters.

The method will also check the hardware requirements and run a self-calibration.

Parameters
initParametersA structure containing all the initial parameters. Default: a preset of InitParameters.
Returns
An error code giving information about the internal process. If ERROR_CODE.SUCCESS is returned, the camera is ready to use. Every other code indicates an error and the program should be stopped.

◆ Close()

void Close ( )
inline

Closes the camera.

Once destroyed, you need to recreate a camera instance to restart again.

◆ Grab()

sl.ERROR_CODE Grab ( ref sl.RuntimeParameters  runtimeParameters)
inline

This method will grab the latest images from the camera, rectify them, and compute the measurements based on the RuntimeParameters provided (depth, point cloud, tracking, etc.).

The grabbing method is typically called in the main loop in a separate thread.

Note
For more info, read about the SDK method it calls: grab.
Parameters
runtimeParametersA structure containing all the runtime parameters. Default: a preset of RuntimeParameters.
Returns
false if no problem was encountered, true otherwise.

◆ StartPublishing()

ERROR_CODE StartPublishing ( ref CommunicationParameters  commParams)
inline

Set this camera as a data provider for the Fusion module.

Parameters
jsonConfigFileName
Returns
ERROR_CODE "ERROR_CODE.SUCCESS" if everything went fine, ERROR_CODE.FAILURE otherwise.

◆ StopPublishing()

ERROR_CODE StopPublishing ( )
inline

Set this camera as normal camera(without data providing).

◆ GetInputType()

sl.INPUT_TYPE GetInputType ( )
inline

Return the sl.INPUT_TYPE currently used.

Returns
The current sl.INPUT_TYPE.

◆ RetrieveImage()

sl.ERROR_CODE RetrieveImage ( sl.Mat  mat,
sl.VIEW  view,
sl.MEM  mem = sl.MEM.CPU,
sl.Resolution  resolution = new sl.Resolution() 
)
inline

Retrieves an image texture from the ZED SDK and loads it into a sl.Mat.

Use this to get an individual texture from the last grabbed frame in a human-viewable format. Image textures work for when you want the result to be visible, such as the direct RGB image from the camera, or a greyscale image of the depth. However it will lose accuracy if used to show measurements like depth or confidence, unlike measure textures.

Note
If you want to access the texture via script, you'll usually want to specify CPU memory. Then you can use Marshal.Copy to move them into a new byte array, which you can load into a Texture2D. Note that you may need to change the color space and/or flip the image.


Note
For more info, read about the SDK method it calls: retrieveImage.
Parameters
matsl.Mat to fill with the new texture.
viewImage type (left RGB, right depth map, etc.)
memWhether the image should be on CPU or GPU memory.
resolutionResolution of the texture.
Returns
sl.ERROR_CODE indicating if the retrieval was successful, and why it wasn't otherwise.

◆ GetInitParameters()

InitParameters GetInitParameters ( )
inline

Returns the InitParameters associated with the Camera object.

It corresponds to the structure given as argument to Open() method.

Returns
InitParameters containing the parameters used to initialize the Camera object.

◆ GetRuntimeParameters()

RuntimeParameters GetRuntimeParameters ( )
inline

Returns the RuntimeParameters used.

It corresponds to the structure given as argument to the Grab() method.

Returns
RuntimeParameters containing the parameters that define the behavior of the Grab method.

◆ GetPositionalTrackingParameters()

PositionalTrackingParameters GetPositionalTrackingParameters ( )
inline

Returns the PositionalTrackingParameters used.

It corresponds to the structure given as argument to the EnablePositionalTracking() method.

Returns
PositionalTrackingParameters containing the parameters used for positional tracking initialization.

◆ GetResolution()

static sl.Resolution GetResolution ( RESOLUTION  resolution)
inlinestatic

Gets the corresponding sl.Resolution from an sl.RESOLUTION.

Parameters
resolutionThe wanted sl.RESOLUTION.
Returns
The sl.Resolution corresponding to sl.RESOLUTION given as argument.

◆ IsCameraSettingSupported()

bool IsCameraSettingSupported ( VIDEO_SETTINGS  setting)
inline

Test if the video setting is supported by the camera.

Parameters
settingThe video setting to test.
Returns
true if the VIDEO_SETTINGS is supported by the camera, false otherwise.

◆ SetCameraSettings() [1/3]

void SetCameraSettings ( VIDEO_SETTINGS  settings,
int  minvalue,
int  maxvalue 
)
inline

Sets the min and max range values of the requested camera setting (used for settings with a range).

Parameters
settingsThe setting to be set.
minvalueThe min value of the range to set.
maxvalueThe min value of the range to set.

Referenced by Camera.ResetCameraSettings().

◆ GetCameraSettings() [1/3]

sl.ERROR_CODE GetCameraSettings ( VIDEO_SETTINGS  settings,
ref int  minvalue,
ref int  maxvalue 
)
inline

Returns the current range of the requested camera setting.

Parameters
settingsSetting to be retrieved (setting with range value).
minvalueWill be set to the value of the lower bound of the range of the setting.
maxvalueWill be set to the value of the higher bound of the range of the setting.
Returns
An sl.ERROR_CODE to indicate if the method was successful.

◆ SetCameraSettings() [2/3]

void SetCameraSettings ( VIDEO_SETTINGS  settings,
int  value 
)
inline

Sets the value of the requested camera setting (gain, brightness, hue, exposure, etc.).

Parameters
settingsThe setting to be set.
valueThe value to set. Default: auto mode

◆ GetCameraSettings() [2/3]

int GetCameraSettings ( VIDEO_SETTINGS  settings)
inline

Returns the current value of the requested camera setting (gain, brightness, hue, exposure, etc.).

Parameters
settingsSetting to be retrieved (brightness, contrast, gain, exposure, etc.).
Returns
The value of the requested camera setting.

◆ SetCameraSettings() [3/3]

ERROR_CODE SetCameraSettings ( VIDEO_SETTINGS  settings,
SIDE  side,
Rect  roi,
bool  reset = false 
)
inline

Overloaded method for VIDEO_SETTINGS.AEC_AGC_ROI which takes a Rect as parameter.

Parameters
settingsMust be set at VIDEO_SETTINGS.AEC_AGC_ROI, otherwise the method will have no impact.
sidesl.SIDE on which to be applied for AEC/AGC computation.
roiRect that defines the target to be applied for AEC/AGC computation. Must be given according to camera resolution.
resetCancel the manual ROI and reset it to the full image.
Returns
An sl.ERROR_CODE to indicate if the method was successful.

◆ GetCameraSettings() [3/3]

ERROR_CODE GetCameraSettings ( VIDEO_SETTINGS  settings,
SIDE  side,
ref Rect  roi 
)
inline

Overloaded method for VIDEO_SETTINGS.AEC_AGC_ROI which takes a Rect as parameter.

Parameters
settingsMust be set at VIDEO_SETTINGS.AEC_AGC_ROI, otherwise the method will have no impact.
sidesl.SIDE on which to get the ROI from.
roiRoi that will be filled.
Returns
An sl.ERROR_CODE to indicate if the method was successful.

◆ ResetCameraSettings()

void ResetCameraSettings ( )
inline

Reset camera settings to default.

◆ GetCameraTimeStamp()

ulong GetCameraTimeStamp ( )
inline

Gets the timestamp at the time the latest grabbed frame was extracted from the USB stream.

This is the closest timestamp you can get from when the image was taken.

Note
Must be called after calling Grab().
Returns
Current timestamp in nanoseconds. -1 means it's is not available, such as with an .SVO file without compression.

◆ GetCurrentTimeStamp()

ulong GetCurrentTimeStamp ( )
inline

Gets the current timestamp at the time the method is called.

Can be compared to the camera timestamp for synchronization, since they have the same reference (the computer's start time).

Returns
The timestamp in nanoseconds.

◆ GetSVOPosition()

int GetSVOPosition ( )
inline

Returns the current playback position in the SVO file.

Returns
The current frame position in the SVO file. -1 if the SDK is not reading an SVO.

◆ GetSVOPositionAtTimestamp()

int GetSVOPositionAtTimestamp ( ulong  timestamp)
inline

Retrieves the frame index within the SVO file corresponding to the provided timestamp.

Parameters
timestampThe target timestamp for which the frame index is to be determined.
Returns
The frame index within the SVO file that aligns with the given timestamp. Returns -1 if the timestamp falls outside the bounds of the SVO file.

◆ GetSVONumberOfFrames()

int GetSVONumberOfFrames ( )
inline

Returns the number of frames in the SVO file.

Returns
The total number of frames in the SVO file. -1 if the SDK is not reading a SVO.

◆ SetSVOPosition()

void SetSVOPosition ( int  frame)
inline

Sets the position of the SVO file currently being read to a desired frame.

Parameters
frameIndex of the desired frame to be decoded.

◆ GetCameraFPS()

float GetCameraFPS ( )
inline

Returns the current camera FPS.

This is limited primarily by resolution but can also be lower due to setting a lower desired resolution in Open() or from USB connection/bandwidth issues.

Returns
The current fps

◆ IsOpened()

bool IsOpened ( )
inline

Reports if the camera has been successfully opened.

Returns
Returns true if the camera is already setup, otherwise false.

◆ GetCalibrationParameters()

CalibrationParameters GetCalibrationParameters ( bool  raw = false)
inline

Return the calibration parameters of the camera.

Parameters
rawWhether to return the raw or rectified calibration parameters.
Returns
CalibrationParameters containing the calibration parameters requested.

Referenced by Camera.GetFOV(), and Camera.Open().

◆ GetCameraModel()

sl.MODEL GetCameraModel ( )
inline

Gets the camera model (sl.MODEL).

Returns
Model of the camera as sl.MODEL.

Referenced by Camera.Open().

◆ GetCameraFirmwareVersion()

int GetCameraFirmwareVersion ( )
inline

Gets the camera firmware version.

Returns
The firmware version of the camera.

◆ GetSensorsFirmwareVersion()

int GetSensorsFirmwareVersion ( )
inline

Gets the sensors firmware version.

Returns
The firmware version of the camera.

◆ GetZEDSerialNumber()

int GetZEDSerialNumber ( )
inline

Gets the camera's serial number.

Returns
The serial number of the camera.

◆ GetFOV()

float GetFOV ( )
inline

Returns the camera's vertical field of view in radians.

Returns
The vertical field of view.

◆ UpdateSelfCalibration()

void UpdateSelfCalibration ( )
inline

Perform a new self calibration process.

In some cases, due to temperature changes or strong vibrations, the stereo calibration becomes less accurate.
Use this method to update the self-calibration data and get more reliable depth values.

Note
The self calibration will occur at the next Grab() call. New values will then be available in GetCameraInformation(), be sure to get them to still have consistent 2D - 3D conversion.

◆ GetFrameDroppedCount()

uint GetFrameDroppedCount ( )
inline

Gets the number of frames dropped since Grab() was called for the first time.

It is based on camera timestamps and an FPS comparison.

Note
It is similar to the Frame Drop display in the ZED Explorer app.
Returns
Frames dropped since first Grab() call.

◆ GetSDKVersion() [1/2]

static string GetSDKVersion ( )
inlinestatic

Gets the version of the currently installed ZED SDK.

Returns
ZED SDK version as a string in the format MAJOR.MINOR.PATCH.

◆ ConvertCoordinateSystem()

static sl.ERROR_CODE ConvertCoordinateSystem ( ref Quaternion  rotation,
ref Vector3  translation,
sl.COORDINATE_SYSTEM  coordinateSystemSrc,
sl.COORDINATE_SYSTEM  coordinateSystemDest 
)
inlinestatic

Change the coordinate system of a transform matrix.

Parameters
rotation[In, Out] : rotation to transform
translation[In, Out] : translation to transform
coordinateSystemSrcThe current coordinate system of the translation/rotation
coordinateSystemDestThe destination coordinate system for the translation/rotation.
Returns
SUCCESS if everything went well, FAILURE otherwise.

◆ GetSDKVersion() [2/2]

static void GetSDKVersion ( ref int  major,
ref int  minor,
ref int  patch 
)
inlinestatic

Gets the version of the currently installed ZED SDK.

Returns
ZED SDK version as a string in the format MAJOR.MINOR.PATCH.

◆ GetDeviceList()

static sl.DeviceProperties [] GetDeviceList ( out int  nbDevices)
inlinestatic

List all the connected devices with their associated information.

This method lists all the cameras available and provides their serial number, models and other information.

Returns
The device properties for each connected camera.

◆ GetStreamingDeviceList()

static sl.StreamingProperties [] GetStreamingDeviceList ( out int  nbDevices)
inlinestatic

List all the streaming devices with their associated information.

This method lists all the cameras available and provides their serial number, models and other information.

Returns
The device properties for each connected camera.

◆ Reboot()

static sl.ERROR_CODE Reboot ( int  serialNumber,
bool  fullReboot = true 
)
inlinestatic

Performs a hardware reset of the ZED 2 and the ZED 2i.

Parameters
serialNumberSerial number of the camera to reset, or 0 to reset the first camera detected.
fullRebootPerform a full reboot (sensors and video modules) if true, otherwise only the video module will be rebooted.
Returns
sl.ERROR_CODE.SUCCESS if everything went fine, sl.ERROR_CODE::CAMERA_NOT_DETECTED if no camera was detected, sl.ERROR_CODE.FAILURE otherwise.

◆ RetrieveMeasure()

sl.ERROR_CODE RetrieveMeasure ( sl.Mat  mat,
sl.MEASURE  measure,
sl.MEM  mem = sl.MEM.CPU,
sl.Resolution  resolution = new sl.Resolution() 
)
inline

Retrieves a measure texture from the ZED SDK and loads it into a sl.Mat.

Use this to get an individual texture from the last grabbed frame with measurements in every pixel - such as a depth map, confidence map, etc. Measure textures are not human-viewable but don't lose accuracy, unlike image textures.

Note
If you want to access the texture via script, you'll usually want to specify CPU memory. Then you can use Marshal.Copy to move them into a new byte array, which you can load into a Texture2D.


Note
For more info, read about the SDK method it calls: retrieveMeasure.
Parameters
matsl.Mat to fill with the new texture.
measureMeasure type (depth, confidence, xyz, etc.).
memWhether the image should be on CPU or GPU memory.
resolutionResolution of the texture.
Returns
sl.ERROR_CODE indicating if the retrieval was successful, and why it wasn't otherwise.

◆ GetConfidenceThreshold()

int GetConfidenceThreshold ( )
inline

Gets the current confidence threshold value for the disparity map (and by extension the depth map).

Values below the given threshold are removed from the depth map.

Returns
Filtering value between 0 and 100.

◆ GetDepthMinRangeValue()

float GetDepthMinRangeValue ( )
inline

Gets the closest measurable distance by the camera, according to the camera type and depth map parameters.

Returns
The nearest possible depth value.

◆ GetCurrentMixMaxDepth()

sl.ERROR_CODE GetCurrentMixMaxDepth ( ref float  min,
ref float  max 
)
inline

Gets the current range of perceived depth.

Parameters
minMinimum depth detected (in selected sl.UNIT).
maxMaximum depth detected (in selected sl.UNIT).
Returns
sl.ERROR_CODE.SUCCESS if values have been extracted. Other sl.ERROR_CODE otherwise.

◆ GetDepthMaxRangeValue()

float GetDepthMaxRangeValue ( )
inline

Returns the current maximum distance of depth/disparity estimation.

Returns
The closest depth

◆ EnablePositionalTracking()

sl.ERROR_CODE EnablePositionalTracking ( ref PositionalTrackingParameters  positionalTrackingParameters)
inline

Initializes and starts the positional tracking processes.

Parameters
positionalTrackingParametersA structure containing all the specific parameters for the positional tracking. Default: a preset of PositionalTrackingParameters.
Returns
sl.ERROR_CODE.FAILURE if the area_file_path file wasn't found, sl.ERROR_CODE.SUCCESS otherwise.

◆ DisablePositionalTracking()

void DisablePositionalTracking ( string  path = "")
inline

Disables the positional tracking.

Parameters
pathIf set, saves the spatial memory into an '.area' file. Default: (empty)
path is the name and path of the database, e.g. path/to/file/myArea1.area".

◆ IsPositionalTrackingEnabled()

bool IsPositionalTrackingEnabled ( )
inline

Tells if the tracking module is enabled.

◆ SaveAreaMap()

ERROR_CODE SaveAreaMap ( string  areaFilePath)
inline

Saves the current area learning file.

The file will contain spatial memory data generated by the tracking.

Parameters
areaFilePathPath of an '.area' file to save the spatial memory database in.

◆ GetAreaExportState()

AREA_EXPORT_STATE GetAreaExportState ( )
inline

Returns the state of the spatial memory export process.

Returns
The current state of the spatial memory export process.

◆ ResetPositionalTracking()

sl.ERROR_CODE ResetPositionalTracking ( Quaternion  rotation,
Vector3  translation 
)
inline

Resets the tracking, and re-initializes the position with the given translation vector and rotation quaternion.

Parameters
rotationRotation to set the positional tracking to.
translationTranslation to set the positional tracking to.
Returns
sl.ERROR_CODE.SUCCESS if the tracking has been reset, sl.ERROR_CODE.FAILURE otherwise.

◆ GetSensorsConfiguration()

SensorsConfiguration GetSensorsConfiguration ( )
inline

Returns the sensor configuration of the camera.

Returns
SensorsConfiguration containing the sensor calibration information of the camera.

◆ GetCameraInformation()

CameraInformation GetCameraInformation ( Resolution  resolution = new Resolution())
inline

Returns the CameraInformation associated the camera being used.

To ensure accurate calibration, it is possible to specify a custom resolution as a parameter when obtaining scaled information, as calibration parameters are resolution-dependent.
When reading an SVO file, the parameters will correspond to the camera used for recording.

Returns
CameraInformation containing the calibration parameters of the camera, as well as serial number and firmware version.

Referenced by Camera.Open().

◆ GetPosition() [1/4]

POSITIONAL_TRACKING_STATE GetPosition ( ref Quaternion  rotation,
ref Vector3  position,
REFERENCE_FRAME  referenceType = REFERENCE_FRAME.WORLD 
)
inline

Gets the position of the camera and the current state of the camera Tracking.

Parameters
rotationQuaternion filled with the current rotation of the camera depending on its reference frame.
positionVector filled with the current position of the camera depending on its reference frame.
referenceTypeReference frame for setting the rotation/position. REFERENCE_FRAME.CAMERA gives movement relative to the last pose. REFERENCE_FRAME.WORLD gives cumulative movements since tracking started.
Returns
The current state of the tracking process.

◆ GetPositionalTrackingStatus()

PositionalTrackingStatus GetPositionalTrackingStatus ( )
inline

Returns the current status of positional tracking module.

Returns
The current status of positional tracking module.

◆ GetPosition() [2/4]

POSITIONAL_TRACKING_STATE GetPosition ( ref Quaternion  rotation,
ref Vector3  translation,
ref Quaternion  targetQuaternion,
ref Vector3  targetTranslation,
REFERENCE_FRAME  referenceFrame = REFERENCE_FRAME.WORLD 
)
inline

Gets the current position of the camera and state of the tracking, with an optional offset to the tracking frame.

Parameters
rotationQuaternion filled with the current rotation of the camera depending on its reference frame.
positionVector filled with the current position of the camera depending on its reference frame.
targetQuaternionRotational offset applied to the tracking frame.
targetTranslationPositional offset applied to the tracking frame.
referenceFrameReference frame for setting the rotation/position. REFERENCE_FRAME.CAMERA gives movement relative to the last pose. REFERENCE_FRAME.WORLD gives cumulative movements since tracking started.
Returns
The current state of the tracking process.

◆ GetPosition() [3/4]

POSITIONAL_TRACKING_STATE GetPosition ( ref Quaternion  rotation,
ref Vector3  translation,
TRACKING_FRAME  trackingFrame,
REFERENCE_FRAME  referenceFrame = REFERENCE_FRAME.WORLD 
)
inline

Gets the current position of the camera and state of the tracking, with a defined tracking frame.

A tracking frame defines what part of the camera is its center for tracking purposes. See sl.TRACKING_FRAME.

Parameters
rotationQuaternion filled with the current rotation of the camera depending on its reference frame.
positionVector filled with the current position of the camera depending on its reference frame.
trackingFrameCenter of the camera for tracking purposes (left eye, center, right eye).
referenceFrameReference frame for setting the rotation/position. REFERENCE_FRAME.CAMERA gives movement relative to the last pose. REFERENCE_FRAME.WORLD gives cumulative movements since tracking started.
Returns
The current state of the tracking process.

◆ GetPosition() [4/4]

POSITIONAL_TRACKING_STATE GetPosition ( ref Pose  pose,
REFERENCE_FRAME  referenceType = REFERENCE_FRAME.WORLD 
)
inline

Gets the current position of the camera and state of the tracking, filling a Pose struct useful for AR pass-through.

Parameters
poseCurrent pose.
referenceTypeReference frame for setting the rotation/position. REFERENCE_FRAME.CAMERA gives movement relative to the last pose. REFERENCE_FRAME.WORLD gives cumulative movements since tracking started.
Returns
The current state of the tracking process.

◆ SetIMUOrientationPrior()

ERROR_CODE SetIMUOrientationPrior ( ref Quaternion  rotation)
inline

Sets a prior to the IMU orientation (not for MODEL.ZED).

Prior must come from a external IMU, such as the HMD orientation and should be in a time frame that's as close as possible to the camera.

Returns
An sl.ERROR_CODE status.
Parameters
rotationPrior rotation.

◆ GetIMUOrientation()

ERROR_CODE GetIMUOrientation ( ref Quaternion  rotation,
TIME_REFERENCE  referenceTime = TIME_REFERENCE.IMAGE 
)
inline

Gets the rotation given by the IMU.

Note
This method will return ERROR_CODE.INVALID_FUNCTION_CALL with a MODEL.ZED which does not contains internal sensors.
Returns
An sl.ERROR_CODE status.
Parameters
rotationRotation from the IMU.

◆ GetSensorsData()

ERROR_CODE GetSensorsData ( ref SensorsData  data,
TIME_REFERENCE  referenceTime = TIME_REFERENCE.IMAGE 
)
inline

Retrieves the SensorsData (IMU, magnetometer, barometer) at a specific time reference.

Note
This method will return ERROR_CODE.INVALID_FUNCTION_CALL with a MODEL.ZED which does not contains internal sensors.
Parameters
dataThe SensorsData variable to store the data.
referenceTimeDefines the reference from which you want the data to be expressed. Default: REFERENCE_FRAME.WORLD.
Returns
An sl.ERROR_CODE status.

◆ SetRegionOfInterest()

ERROR_CODE SetRegionOfInterest ( sl.Mat  roiMask,
bool[]  module 
)
inline

Defines a region of interest to focus on for all the SDK, discarding other parts.

Parameters
roiMaskThe Mat defining the requested region of interest, pixels lower than 127 will be discarded from all modules: depth, positional tracking, etc. If empty, set all pixels as valid. The mask can be either at lower or higher resolution than the current images.
moduleApply the ROI to a list of SDK module, all by default. Must of size sl.MODULE.LAST. The Mat defining the requested region of interest, pixels lower than 127 will be discarded from all modules: depth, positional tracking, etc. If empty, set all pixels as valid. The mask can be either at lower or higher resolution than the current images.
Returns
An sl.ERROR_CODE if something went wrong.

◆ GetRegionOfInterest()

ERROR_CODE GetRegionOfInterest ( sl.Mat  roiMask,
sl.Resolution  resolution = new sl.Resolution(),
MODULE  module = MODULE.ALL 
)
inline

Get the previously set or computed region of interest.

Parameters
roiMaskThe Mat returned
resolutionThe optional size of the returned mask
moduleSpecifies the module from which the ROI is to be obtained.
Returns
An sl.ERROR_CODE if something went wrong.

◆ StartRegionOfInterestAutoDetection()

ERROR_CODE StartRegionOfInterestAutoDetection ( RegionOfInterestParameters  roiParams)
inline

Start the auto detection of a region of interest to focus on for all the SDK, discarding other parts. This detection is based on the general motion of the camera combined with the motion in the scene. The camera must move for this process, an internal motion detector is used, based on the Positional Tracking module. It requires a few hundreds frames of motion to compute the mask.

Note
This module is expecting a static portion, typically a fairly close vehicle hood at the bottom of the image. This module may not work correctly or detect incorrect background area, especially with slow motion, if there's no static element. This module work asynchronously, the status can be obtained using GetRegionOfInterestAutoDetectionStatus(), the result is either auto applied, or can be retrieve using GetRegionOfInterest function.
Parameters
roiParams
Returns
An sl.ERROR_CODE if something went wrong.

◆ GetRegionOfInterestAutoDetectionStatus()

REGION_OF_INTEREST_AUTO_DETECTION_STATE GetRegionOfInterestAutoDetectionStatus ( )
inline

Return the status of the automatic Region of Interest Detection. The automatic Region of Interest Detection is enabled by using StartRegionOfInterestAutoDetection

Returns
An sl.ERROR_CODE if something went wrong.

◆ EnableSpatialMapping() [1/2]

sl.ERROR_CODE EnableSpatialMapping ( ref SpatialMappingParameters  spatialMappingParameters)
inline

Initializes and begins the spatial mapping processes.

Parameters
spatialMappingParametersSpatial mapping parameters.
Returns
sl.ERROR_CODE.SUCCESS if everything went fine, sl.ERROR_CODE.FAILURE otherwise.

◆ EnableSpatialMapping() [2/2]

sl.ERROR_CODE EnableSpatialMapping ( SPATIAL_MAP_TYPE  type = SPATIAL_MAP_TYPE.MESH,
MAPPING_RESOLUTION  mappingResolution = MAPPING_RESOLUTION.MEDIUM,
MAPPING_RANGE  mappingRange = MAPPING_RANGE.MEDIUM,
bool  saveTexture = false 
)
inline

Initializes and begins the spatial mapping processes.

Parameters
resolutionMeterSpatial mapping resolution in meters.
maxRangeMeterMaximum scanning range in meters.
saveTextureTrue to scan surface textures in addition to geometry.
Returns
sl.ERROR_CODE.SUCCESS if everything went fine, sl.ERROR_CODE.FAILURE otherwise.

◆ GetSpatialMappingParameters()

SpatialMappingParameters GetSpatialMappingParameters ( )
inline

Returns the SpatialMappingParameters used.

It corresponds to the structure given as argument to the EnableSpatialMapping() method.

Returns
SpatialMappingParameters containing the parameters used for spatial mapping initialization.

◆ DisableSpatialMapping()

void DisableSpatialMapping ( )
inline

Disables the spatial mapping process.

◆ UpdateMesh() [1/2]

sl.ERROR_CODE UpdateMesh ( int[]  nbVerticesInSubmeshes,
int[]  nbTrianglesInSubmeshes,
ref int  nbUpdatedSubmesh,
int[]  updatedIndices,
ref int  nbVertices,
ref int  nbTriangles,
int  nbSubmeshMax 
)
inline

Updates the internal version of the mesh and returns the sizes of the meshes.

Parameters
nbVerticesInSubmeshesArray of the number of vertices in each sub-mesh.
nbTrianglesInSubmeshesArray of the number of triangles in each sub-mesh.
nbUpdatedSubmeshNumber of updated sub-meshes.
updatedIndicesList of all sub-meshes updated since the last update.
nbVerticesTotal number of updated vertices in all sub-meshes.
nbTrianglesTotal number of updated triangles in all sub-meshes.
nbSubmeshMaxMaximum number of sub-meshes that can be handled.
Returns
sl.ERROR_CODE indicating if the update was successful, and why it wasn't otherwise.

Referenced by Camera.RetrieveSpatialMap(), and Camera.UpdateMesh().

◆ UpdateMesh() [2/2]

sl.ERROR_CODE UpdateMesh ( ref Mesh  mesh)
inline

Updates the internal version of the mesh and returns the sizes of the meshes.

Parameters
meshThe mesh to be filled with the generated spatial map.
Returns
sl.ERROR_CODE indicating if the update was successful, and why it wasn't otherwise.

◆ RetrieveMesh() [1/2]

sl.ERROR_CODE RetrieveMesh ( Vector3[]  vertices,
int[]  triangles,
byte[]  colors,
int  nbSubmeshMax,
Vector2[]  uvs,
IntPtr  textures 
)
inline

Retrieves all chunks of the current generated mesh.

Note
Call UpdateMesh() before calling this.

Vertex and triangle arrays must be at least of the sizes returned by UpdateMesh (nbVertices and nbTriangles).

Parameters
verticesVertices of the mesh.
trianglesTriangles, formatted as the index of each triangle's three vertices in the vertices array.
colors(b, g, r) colors of the vertices.
nbSubmeshMaxMaximum number of sub-meshes that can be handled.
Returns
sl.ERROR_CODE indicating if the retrieval was successful, and why it wasn't otherwise.

Referenced by Camera.RetrieveMesh(), and Camera.RetrieveSpatialMap().

◆ RetrieveMesh() [2/2]

sl.ERROR_CODE RetrieveMesh ( ref Mesh  mesh)
inline

Retrieves all chunks of the current generated mesh.

Note
Call UpdateMesh() before calling this.

Vertex and triangle arrays must be at least of the sizes returned by UpdateMesh (nbVertices and nbTriangles).

Parameters
meshThe mesh to be filled with the generated spatial map.
Returns
sl.ERROR_CODE indicating if the retrieval was successful, and why it wasn't otherwise.

◆ RetrieveChunks()

sl.ERROR_CODE RetrieveChunks ( ref Mesh  mesh)
inline

Retrieve all chunks of the generated mesh.

Parameters
meshThe mesh to be filled with the generated spatial map.
Returns
sl.ERROR_CODE indicating if the retrieval was successful, and why it wasn't otherwise.

◆ RetrieveSpatialMap() [1/2]

sl.ERROR_CODE RetrieveSpatialMap ( ref Mesh  mesh)
inline

Retrieves the current generated mesh.

Parameters
meshThe mesh to be filled with the generated spatial map.
Returns
sl.ERROR_CODE indicating if the retrieval was successful, and why it wasn't otherwise.

◆ RetrieveSpatialMap() [2/2]

sl.ERROR_CODE RetrieveSpatialMap ( ref FusedPointCloud  fusedPointCloud)
inline

Retrieves the current fused point cloud.

Parameters
fusedPointCloudThe Fused Point Cloud to be filled with the generated spatial map.
Returns
sl.ERROR_CODE indicating if the retrieval was successful, and why it wasn't otherwise.

◆ UpdateFusedPointCloud()

sl.ERROR_CODE UpdateFusedPointCloud ( ref int  nbVertices)
inline

Updates the fused point cloud (if spatial map type was FUSED_POINT_CLOUD).

Returns
sl.ERROR_CODE indicating if the update was successful, and why it wasn't otherwise.

Referenced by Camera.RetrieveSpatialMap().

◆ RetrieveFusedPointCloud()

sl.ERROR_CODE RetrieveFusedPointCloud ( Vector4[]  vertices)
inline

Retrieves all points of the fused point cloud.

Note
Call UpdateFusedPointCloud() before calling this.

Vertex arrays must be at least of the sizes returned by UpdateFusedPointCloud().

Parameters
verticesPoints of the fused point cloud.
Returns
sl.ERROR_CODE indicating if the retrieval was successful, and why it wasn't otherwise.

Referenced by Camera.RetrieveSpatialMap().

◆ ExtractWholeSpatialMap()

ERROR_CODE ExtractWholeSpatialMap ( )
inline

Extracts the current spatial map from the spatial mapping process.

If the object to be filled already contains a previous version of the mesh, only changes will be updated, optimizing performance.

Returns
sl.ERROR_CODE.SUCCESS if the mesh is filled and available, otherwise sl.ERROR_CODE.FAILURE.

This is a blocking method. You should either call it in a thread or at the end of the mapping process.

◆ RequestSpatialMap()

void RequestSpatialMap ( )
inline

Starts the mesh generation process in a thread that does not block the spatial mapping process.

ZEDSpatialMappingHelper calls this each time it has finished applying the last mesh update.

◆ PauseSpatialMapping()

void PauseSpatialMapping ( bool  status)
inline

Pauses or resumes the spatial mapping processes.

Parameters
statusIf true, the integration is paused. If false, the spatial mapping is resumed.

◆ GetMeshRequestStatus()

sl.ERROR_CODE GetMeshRequestStatus ( )
inline

Returns the mesh generation status.

Useful for knowing when to update and retrieve the mesh.

Returns
sl.ERROR_CODE.SUCCESS if the mesh is ready and not yet retrieved, otherwise sl.ERROR_CODE.FAILURE.

◆ SaveMesh()

bool SaveMesh ( string  filename,
MESH_FILE_FORMAT  format 
)
inline

Saves the scanned mesh in a specific file format.

Parameters
filenamePath and filename of the mesh.
formatFile format (extension). Can be .obj, .ply or .bin.
Returns
Has the mesh been saved successfully.

◆ SavePointCloud()

bool SavePointCloud ( string  filename,
MESH_FILE_FORMAT  format 
)
inline

Saves the scanned point cloud in a specific file format.

Parameters
filenamePath and filename of the point cloud.
formatFile format (extension). Can be .obj, .ply or .bin.
Returns
Has the point cloud been saved successfully.

◆ LoadMesh()

bool LoadMesh ( string  filename,
int[]  nbVerticesInSubmeshes,
int[]  nbTrianglesInSubmeshes,
ref int  nbSubmeshes,
int[]  updatedIndices,
ref int  nbVertices,
ref int  nbTriangles,
int  nbSubmeshMax,
int[]  textureSize = null 
)
inline

Loads a saved mesh file.

ZEDSpatialMapping then configures itself as if the loaded mesh was just scanned.

Parameters
filenamePath and filename of the mesh. Should include the extension (.obj, .ply or .bin).
nbVerticesInSubmeshesArray of the number of vertices in each sub-mesh.
nbTrianglesInSubmeshesArray of the number of triangles in each sub-mesh.
nbSubmeshesNumber of sub-meshes.
updatedIndicesList of all sub-meshes updated since the last update.
nbVerticesTotal number of updated vertices in all sub-meshes.
nbTrianglesTotal number of updated triangles in all sub-meshes.
nbSubmeshMaxMaximum number of sub-meshes that can be handled.
textureSizeArray containing the sizes of all the textures (width, height) if applicable.
Returns
Has the mesh been loaded successfully.

◆ FilterMesh() [1/2]

bool FilterMesh ( MESH_FILTER  filterParameters,
int[]  nbVerticesInSubmeshes,
int[]  nbTrianglesInSubmeshes,
ref int  nbSubmeshes,
int[]  updatedIndices,
ref int  nbVertices,
ref int  nbTriangles,
int  nbSubmeshMax 
)
inline

Filters a mesh to remove triangles while still preserving its overall shape (though less accurate).

Parameters
filterParametersFilter level. Higher settings remove more triangles.
nbVerticesInSubmeshesArray of the number of vertices in each sub-mesh.
nbTrianglesInSubmeshesArray of the number of triangles in each sub-mesh.
nbSubmeshesNumber of sub-meshes.
updatedIndicesList of all sub-meshes updated since the last update.
nbVerticesTotal number of updated vertices in all sub-meshes.
nbTrianglesTotal number of updated triangles in all sub-meshes.
nbSubmeshMaxMaximum number of sub-meshes that can be handled.
Returns
Has the mesh been filtered successfully.

◆ FilterMesh() [2/2]

bool FilterMesh ( MESH_FILTER  filterParameters,
ref Mesh  mesh 
)
inline

Filters a mesh to remove triangles while still preserving its overall shape (though less accurate).

Parameters
filterParametersFilter level. Higher settings remove more triangles.
meshThe mesh to be filled with the generated spatial map.
Returns
Has the mesh been filtered successfully.

◆ ApplyTexture() [1/2]

bool ApplyTexture ( int[]  nbVerticesInSubmeshes,
int[]  nbTrianglesInSubmeshes,
ref int  nbSubmeshes,
int[]  updatedIndices,
ref int  nbVertices,
ref int  nbTriangles,
int[]  textureSize,
int  nbSubmeshMax 
)
inline

Applies the scanned texture onto the internal scanned mesh.

Parameters
nbVerticesInSubmeshesArray of the number of vertices in each sub-mesh.
nbTrianglesInSubmeshesArray of the number of triangles in each sub-mesh.
nbSubmeshesNumber of sub-meshes.
updatedIndicesList of all sub-meshes updated since the last update.
nbVerticesTotal number of updated vertices in all sub-meshes.
nbTrianglesTotal number of updated triangles in all sub-meshes.
textureSizeVector containing the size of all the texture (width, height).
nbSubmeshMaxMaximum number of sub-meshes that can be handled.
Returns
Has the texture been applied successfully.

◆ ApplyTexture() [2/2]

bool ApplyTexture ( ref Mesh  mesh)
inline

Applies the texture on a mesh.

Parameters
meshMesh with a texture to apply.
Returns
Has the texture been applied successfully.

◆ GetSpatialMappingState()

SPATIAL_MAPPING_STATE GetSpatialMappingState ( )
inline

Returns the current spatial mapping state.

As the spatial mapping runs asynchronously, this method allows you to get reported errors or status info.

Returns
The current state of the spatial mapping process.

◆ GetGravityEstimate()

Vector3 GetGravityEstimate ( )
inline

Gets a vector pointing toward the direction of gravity.

This is estimated from a 3D scan of the environment, and as such, a scan must be started/finished for this value to be calculated. If using a camera other than MODEL.ZED, this is not required thanks to its IMU.

Returns
Vector3 pointing downward.

◆ MergeChunks()

void MergeChunks ( int  numberFaces,
int[]  nbVerticesInSubmeshes,
int[]  nbTrianglesInSubmeshes,
ref int  nbSubmeshes,
int[]  updatedIndices,
ref int  nbVertices,
ref int  nbTriangles,
int  nbSubmesh 
)
inline

Consolidates the chunks from a scan.

This is used to turn lots of small meshes (which are efficient for the scanning process) into several large meshes (which are more convenient to work with).

Parameters
numberFaces
nbVerticesInSubmeshesArray of the number of vertices in each sub-mesh.
nbTrianglesInSubmeshesArray of the number of triangles in each sub-mesh.
nbSubmeshesNumber of sub-meshes.
updatedIndicesList of all sub-meshes updated since the last update.
nbVerticesTotal number of updated vertices in all sub-meshes.
nbTrianglesTotal number of updated triangles in all sub-meshes.

◆ findFloorPlane()

sl.ERROR_CODE findFloorPlane ( ref PlaneData  plane,
out float  playerHeight,
Quaternion  priorQuat,
Vector3  priorTrans 
)
inline

Detect the floor plane of the scene.

Use ZEDPlaneDetectionManager.DetectFloorPlane for a higher-level version that turns planes into GameObjects.

Parameters
planeData on the detected plane.
playerHeightHeight of the camera from the newly-detected floor.
priorQuatPrior rotation.
priorTransPrior position.
Returns
sl.ERROR_CODE.SUCCESS if everything went fine, sl.ERROR_CODE.FAILURE otherwise.

◆ FindFloorPlane()

sl.ERROR_CODE FindFloorPlane ( ref PlaneData  plane,
out float  playerHeight,
Quaternion  priorQuat,
Vector3  priorTrans 
)
inline

Detect the floor plane of the scene.

Use ZEDPlaneDetectionManager.DetectFloorPlane for a higher-level version that turns planes into GameObjects.

Parameters
planeData on the detected plane.
playerHeightHeight of the camera from the newly-detected floor.
priorQuatPrior rotation.
priorTransPrior position.
Returns
sl.ERROR_CODE.SUCCESS if everything went fine, sl.ERROR_CODE.FAILURE otherwise.

◆ convertFloorPlaneToMesh()

int convertFloorPlaneToMesh ( Vector3[]  vertices,
int[]  triangles,
out int  numVertices,
out int  numTriangles 
)
inline

Using data from a detected floor plane, updates supplied vertex and triangle arrays with data needed to make a mesh that represents it.

These arrays are updated directly from the wrapper.

Parameters
verticesArray to be filled with mesh vertices.
trianglesArray to be filled with mesh triangles, stored as indexes of each triangle's points.
numVerticesTotal vertices in the mesh.
numTrianglesTotal triangle indexes (3x number of triangles).
Returns
0 is the method was successful, 1 otherwise.

◆ ConvertFloorPlaneToMesh()

int ConvertFloorPlaneToMesh ( Vector3[]  vertices,
int[]  triangles,
out int  numVertices,
out int  numTriangles 
)
inline

Using data from a detected floor plane, updates supplied vertex and triangle arrays with data needed to make a mesh that represents it.

These arrays are updated directly from the wrapper.

Parameters
verticesArray to be filled with mesh vertices.
trianglesArray to be filled with mesh triangles, stored as indexes of each triangle's points.
numVerticesTotal vertices in the mesh.
numTrianglesTotal triangle indexes (3x number of triangles).
Returns
0 is the method was successful, 1 otherwise.

◆ findPlaneAtHit()

sl.ERROR_CODE findPlaneAtHit ( ref PlaneData  plane,
Vector2  coord,
ref PlaneDetectionParameters  planeDetectionParameters 
)
inline

Checks the plane at the given left image coordinates.

Parameters
planeThe detected plane if the method succeeded.
coordThe image coordinate. The coordinate must be taken from the full-size image.
parametersA structure containing all the specific parameters for the plane detection. Default: a preset of PlaneDetectionParameters.
Returns
sl.ERROR_CODE.SUCCESS if everything went fine, sl.ERROR_CODE.FAILURE otherwise.

◆ FindPlaneAtHit()

sl.ERROR_CODE FindPlaneAtHit ( ref PlaneData  plane,
Vector2  coord,
ref PlaneDetectionParameters  planeDetectionParameters 
)
inline

Checks the plane at the given left image coordinates.

Parameters
planeThe detected plane if the method succeeded.
coordThe image coordinate. The coordinate must be taken from the full-size image.
parametersA structure containing all the specific parameters for the plane detection. Default: a preset of PlaneDetectionParameters.
Returns
sl.ERROR_CODE.SUCCESS if everything went fine, sl.ERROR_CODE.FAILURE otherwise.

◆ convertHitPlaneToMesh()

int convertHitPlaneToMesh ( Vector3[]  vertices,
int[]  triangles,
out int  numVertices,
out int  numTriangles 
)
inline

Using data from a detected hit plane, updates supplied vertex and triangle arrays with data needed to make a mesh that represents it.

These arrays are updated directly from the wrapper.

Parameters
verticesArray to be filled with mesh vertices.
trianglesArray to be filled with mesh triangles, stored as indexes of each triangle's points.
numVerticesTotal vertices in the mesh.
numTrianglesTotal triangle indexes (3x number of triangles).
Returns
0 is the method was successful, 1 otherwise.

◆ ConvertHitPlaneToMesh()

int ConvertHitPlaneToMesh ( Vector3[]  vertices,
int[]  triangles,
out int  numVertices,
out int  numTriangles 
)
inline

Using data from a detected hit plane, updates supplied vertex and triangle arrays with data needed to make a mesh that represents it.

These arrays are updated directly from the wrapper.

Parameters
verticesArray to be filled with mesh vertices.
trianglesArray to be filled with mesh triangles, stored as indexes of each triangle's points.
numVerticesTotal vertices in the mesh.
numTrianglesTotal triangle indexes (3x number of triangles).
Returns
0 is the method was successful, 1 otherwise.

◆ ConvertRangePreset()

static float ConvertRangePreset ( MAPPING_RANGE  rangePreset)
inlinestatic

Updates the range to match the specified preset.

Referenced by Camera.EnableSpatialMapping().

◆ ConvertResolutionPreset()

static float ConvertResolutionPreset ( MAPPING_RESOLUTION  resolutionPreset)
inlinestatic

Updates the resolution to match the specified preset.

Referenced by Camera.EnableSpatialMapping().

◆ EnableRecording() [1/2]

ERROR_CODE EnableRecording ( string  videoFileName,
SVO_COMPRESSION_MODE  compressionMode = SVO_COMPRESSION_MODE.H264_BASED,
uint  bitrate = 0,
int  targetFPS = 0,
bool  transcode = false 
)
inline

Creates an SVO file to be filled by EnableRecording() and DisableRecording().

Note
An SVO is Stereolabs' own format designed for the ZED. It holds the video feed with timestamps as well as info about the camera used to record it.
Parameters
videoFileNameFilename of the recording. Whether it ends with .svo or .avi defines its file type.
compressionModeThe compression to use for recording.
bitrateOverride default bitrate with a custom bitrate (Kbits/s).
targetFPSUse another fps than camera FPS. Must respect camera_fpstarget_fps == 0.
transcodeIf input is in streaming mode, dump directly into SVO file (transcode=false) or decode/encode (transcode=true).
Returns
An sl.ERROR_CODE that defines if the file was successfully created and can be filled with images.

◆ EnableRecording() [2/2]

ERROR_CODE EnableRecording ( RecordingParameters  recordingParameters)
inline

Creates an SVO file to be filled by EnableRecording() and DisableRecording().

Parameters
videoFileNameA structure containing all the specific parameters for the positional tracking. Default: a reset of RecordingParameters.
Returns
An sl.ERROR_CODE that defines if the file was successfully created and can be filled with images.

◆ GetRecordingStatus()

sl.RecordingStatus GetRecordingStatus ( )
inline

Get the recording information.

Returns
The recording state structure. For more details, see RecordingStatus.

◆ GetRecordingParameters()

sl.RecordingParameters GetRecordingParameters ( )
inline

Returns the RecordingParameters used.

It corresponds to the structure given as argument to the EnableRecording() method.

Returns
sl.RecordingParameters containing the parameters used for recording initialization.

◆ PauseRecording()

void PauseRecording ( bool  status)
inline

Pauses or resumes the recording.

Parameters
statusIf true, the recording is paused. If false, the recording is resumed.

◆ DisableRecording()

void DisableRecording ( )
inline

Disables the recording initiated by EnableRecording() and closes the generated file.

◆ IngestDataIntoSVO()

ERROR_CODE IngestDataIntoSVO ( ref SVOData  data)
inline

Ingest SVOData in a SVO file.

Parameters
dataData to ingest in the SVO file..

Note: The method works only if the camera is recording.

Returns

◆ RetrieveSVOData()

ERROR_CODE RetrieveSVOData ( string  key,
ref List< SVOData data,
ulong  tsBegin,
ulong  tsEnd 
)
inline

Retrieves SVO data from the SVO file at the given channel key and in the given timestamp range.

Parameters
keyThe key of the SVOData that is going to be retrieved.
dataThe map to be filled with SVOData objects, with timestamps as keys.
tsBeginThe beginning of the range.
tsEndThe end of the range.
Returns
sl.ERROR_CODE.SUCCESS in case of success, sl.ERROR_CODE.FAILURE otherwise.

◆ GetSVODataKeys()

List<string> GetSVODataKeys ( )
inline

Gets the external channels that can be retrieved from the SVO file.

Returns
List of available keys.

◆ EnableStreaming() [1/2]

ERROR_CODE EnableStreaming ( STREAMING_CODEC  codec = STREAMING_CODEC.H264_BASED,
uint  bitrate = 8000,
ushort  port = 30000,
int  gopSize = -1,
bool  adaptativeBitrate = false,
int  chunkSize = 32768,
int  targetFPS = 0 
)
inline

Creates an streaming pipeline.

Parameters
codecDefines the codec used for streaming.
bitrateDefines the streaming bitrate in Kbits/s.
portDefines the port used for streaming.
gopSizeDefines the gop size in number of frames.
adaptativeBitrateEnable/Disable adaptive bitrate.
chunkSizeDefines a single chunk size.
targetFPSDefines the target framerate for the streaming output.
Returns
An sl.ERROR_CODE that defines if the streaming pipe was successfully created.

◆ EnableStreaming() [2/2]

ERROR_CODE EnableStreaming ( ref StreamingParameters  streamingParameters)
inline

Creates an streaming pipeline.

Parameters
streamingParametersA structure containing all the specific parameters for the streaming. Default: a preset of StreamingParameters.
Returns
An sl.ERROR_CODE that defines if the streaming pipe was successfully created.

◆ IsStreamingEnabled()

bool IsStreamingEnabled ( )
inline

Tells if the streaming is running.

Returns
Has the streaming been enabled successfully.

◆ DisableStreaming()

void DisableStreaming ( )
inline

Disables the streaming initiated by EnableStreaming().

◆ GetStreamingParameters()

sl.StreamingParameters GetStreamingParameters ( )
inline

Returns the StreamingParameters used.

It corresponds to the structure given as argument to the EnableStreaming() method.

Returns
sl.StreamingParameters containing the parameters used for streaming initialization.

◆ SaveCurrentImageInFile()

sl.ERROR_CODE SaveCurrentImageInFile ( sl.VIEW  view,
String  filename 
)
inline

Save current image (specified by view) in a file defined by filename.

Supported formats are JPEG and PNG.
Filename must end with either .jpg or .png.

Parameters
sidesl.SIDE on which to save the image.
filenameFilename must end with .jpg or .png.
Returns
An sl.ERROR_CODE that indicates the type of error.

◆ SaveCurrentDepthInFile()

sl.ERROR_CODE SaveCurrentDepthInFile ( SIDE  side,
String  filename 
)
inline

Save the current depth in a file defined by filename.

Supported formats are PNG, PFM and PGM.

Parameters
sidesl.SIDE on which to save the depth.
filenameFilename must end with .png, .pfm or .pgm.
Returns
An sl.ERROR_CODE that indicates the type of error.

◆ SaveCurrentPointCloudInFile()

sl.ERROR_CODE SaveCurrentPointCloudInFile ( SIDE  side,
String  filename 
)
inline

Save the current point cloud in a file defined by filename.

Supported formats are PLY, VTK, XYZ and PCD.

Parameters
sidesl.SIDE on which to save the point cloud.
filenameFilename must end with .ply, .xyz , .vtk or .pcd.
Returns
An sl.ERROR_CODE that indicates the type of error.

◆ CheckAIModelStatus()

static AI_Model_status CheckAIModelStatus ( AI_MODELS  model,
int  gpu_id = 0 
)
inlinestatic

Check if a corresponding optimized engine is found for the requested model based on your rig configuration.

Parameters
modelAI model to check.
gpu_idID of the gpu.
Returns
The status of the AI model.

◆ OptimizeAIModel()

static sl.ERROR_CODE OptimizeAIModel ( AI_MODELS  model,
int  gpu_id = 0 
)
inlinestatic

Optimize the requested model, possible download if the model is not present on the host.

Parameters
modelAI model to optimize.
gpu_idID of the gpu to optimize on.
Returns
An sl.ERROR_CODE that indicates the type of error.

◆ EnableObjectDetection()

sl.ERROR_CODE EnableObjectDetection ( ref ObjectDetectionParameters  od_params)
inline

Initializes and starts object detection module.

Parameters
od_paramsA structure containing all the specific parameters for the object detection. Default: a preset of ObjectDetectionParameters.
Returns
An sl.ERROR_CODE that indicates the type of error.

◆ EnableBodyTracking()

sl.ERROR_CODE EnableBodyTracking ( ref BodyTrackingParameters  bt_params)
inline

Initializes and starts body tracking module.

Parameters
bt_paramsA structure containing all the specific parameters for the body tracking. Default: a preset of BodyTrackingParameters.
Returns
An sl.ERROR_CODE that indicates the type of error.

◆ DisableObjectDetection()

void DisableObjectDetection ( uint  instanceID = 0,
bool  disableAllInstance = false 
)
inline

Disable object detection module and release the resources.

Parameters
instanceIDId of the object detection instance. Used when multiple instances of the object detection module are enabled at the same time.
disableAllInstanceShould disable all instances of the object detection module or just instanceID.

◆ DisableBodyTracking()

void DisableBodyTracking ( uint  instanceID = 0,
bool  disableAllInstance = false 
)
inline

Disable body tracking module and release the resources.

Parameters
instanceIDId of the body tracking module instance. Used when multiple instances of the body tracking module module are enabled at the same time.
disableAllInstanceShould disable all instances of the body tracking module or just instanceID.

◆ GetObjectDetectionParameters()

sl.ObjectDetectionParameters GetObjectDetectionParameters ( )
inline

Returns the ObjectDetectionParameters used.

It corresponds to the structure given as argument to the EnableObjectDetection() method.

Returns
sl.ObjectDetectionParameters containing the parameters used for object detection initialization.

◆ GetBodyTrackingParameters()

sl.BodyTrackingParameters GetBodyTrackingParameters ( )
inline

Returns the BodyTrackingParameters used.

It corresponds to the structure given as argument to the EnableBodyTracking() method.

Returns
sl.BodyTrackingParameters containing the parameters used for body tracking initialization.

◆ IngestCustomBoxObjects()

sl.ERROR_CODE IngestCustomBoxObjects ( List< CustomBoxObjectData objects_in)
inline

Feed the 3D Object tracking method with your own 2D bounding boxes from your own detection algorithm.

Parameters
objects_inList of CustomBoxObjectData to feed the object detection.
instanceIDId of the object detection instance. Used when multiple instances of the object detection module are enabled at the same time.
Returns
sl.ERROR_CODE.SUCCESS if everything went fine.

◆ RetrieveObjects()

sl.ERROR_CODE RetrieveObjects ( ref Objects  objs,
ref ObjectDetectionRuntimeParameters  od_params,
uint  instanceID = 0 
)
inline

Retrieve objects detected by the object detection module.

Parameters
objsRetrieved objects.
od_paramsObject detection runtime parameters
instanceIDId of the object detection instance. Used when multiple instances of the object detection module are enabled at the same time.
Returns
sl.ERROR_CODE.SUCCESS if everything went fine, sl.ERROR_CODE.FAILURE otherwise.

◆ RetrieveBodies()

sl.ERROR_CODE RetrieveBodies ( ref Bodies  objs,
ref BodyTrackingRuntimeParameters  bt_params,
uint  instanceID = 0 
)
inline

Retrieve bodies detected by the body tracking module.

Parameters
objsRetrieved bodies.
bt_paramsBody tracking runtime parameters
instanceIDId of the body tracking instance. Used when multiple instances of the body tracking module are enabled at the same time.
Returns
sl.ERROR_CODE.SUCCESS if everything went fine, sl.ERROR_CODE.FAILURE otherwise.

◆ UpdateObjectsBatch()

sl.ERROR_CODE UpdateObjectsBatch ( out int  nbBatches)
inline

Update the batch trajectories and retrieve the number of batches.

Parameters
nbBatchesNumbers of batches.
Returns
An sl.ERROR_CODE that indicates the type of error.

◆ GetObjectsBatch()

sl.ERROR_CODE GetObjectsBatch ( int  batch_index,
ref ObjectsBatch  objectsBatch 
)
inline

Retrieve a batch of objects.

Note
This method need to be called after RetrieveObjects(), otherwise trajectories will be empty.
It also needs to be called after UpdateObjectsBatch() in order to retrieve the number of batch trajectories.
To retrieve all the objects' batches, you need to iterate from 0 to nbBatches (retrieved from UpdateObjectsBatch()).
Parameters
batch_indexIndex of the batch retrieved.
objectsBatchTrajectory that will be filled by the batching queue process.
Returns
An sl.ERROR_CODE that indicates the type of error.

Variables

◆ CameraID

int CameraID = 0

Camera ID (for multiple cameras)

Referenced by Camera.ApplyTexture(), Camera.Camera(), Camera.Close(), Camera.convertFloorPlaneToMesh(), Camera.ConvertFloorPlaneToMesh(), Camera.convertHitPlaneToMesh(), Camera.ConvertHitPlaneToMesh(), Camera.DisableBodyTracking(), Camera.DisableObjectDetection(), Camera.DisablePositionalTracking(), Camera.DisableRecording(), Camera.DisableSpatialMapping(), Camera.DisableStreaming(), Camera.EnableBodyTracking(), Camera.EnableObjectDetection(), Camera.EnablePositionalTracking(), Camera.EnableRecording(), Camera.EnableSpatialMapping(), Camera.EnableStreaming(), Camera.ExtractWholeSpatialMap(), Camera.FilterMesh(), Camera.findFloorPlane(), Camera.FindFloorPlane(), Camera.findPlaneAtHit(), Camera.FindPlaneAtHit(), Camera.GetAreaExportState(), Camera.GetBodyTrackingParameters(), Camera.GetCalibrationParameters(), Camera.GetCameraFirmwareVersion(), Camera.GetCameraFPS(), Camera.GetCameraInformation(), Camera.GetCameraModel(), Camera.GetCameraSettings(), Camera.GetCameraTimeStamp(), Camera.GetConfidenceThreshold(), Camera.GetCurrentMixMaxDepth(), Camera.GetCurrentTimeStamp(), Camera.GetDepthMaxRangeValue(), Camera.GetDepthMinRangeValue(), Camera.GetFrameDroppedCount(), Camera.GetGravityEstimate(), Camera.GetIMUOrientation(), Camera.GetInitParameters(), Camera.GetInputType(), Camera.GetMeshRequestStatus(), Camera.GetObjectDetectionParameters(), Camera.GetObjectsBatch(), Camera.GetPosition(), Camera.GetPositionalTrackingParameters(), Camera.GetPositionalTrackingStatus(), Camera.GetRecordingParameters(), Camera.GetRecordingStatus(), Camera.GetRegionOfInterest(), Camera.GetRegionOfInterestAutoDetectionStatus(), Camera.GetRuntimeParameters(), Camera.GetSensorsConfiguration(), Camera.GetSensorsData(), Camera.GetSensorsFirmwareVersion(), Camera.GetSpatialMappingParameters(), Camera.GetSpatialMappingState(), Camera.GetStreamingParameters(), Camera.GetSVODataKeys(), Camera.GetSVONumberOfFrames(), Camera.GetSVOPosition(), Camera.GetSVOPositionAtTimestamp(), Camera.GetZEDSerialNumber(), Camera.Grab(), Camera.IngestCustomBoxObjects(), Camera.IngestDataIntoSVO(), Camera.IsCameraSettingSupported(), Camera.IsOpened(), Camera.IsPositionalTrackingEnabled(), Camera.IsStreamingEnabled(), Camera.LoadMesh(), Camera.MergeChunks(), Camera.Open(), Camera.PauseRecording(), Camera.PauseSpatialMapping(), Camera.RequestSpatialMap(), Camera.ResetPositionalTracking(), Camera.RetrieveBodies(), Camera.RetrieveChunks(), Camera.RetrieveFusedPointCloud(), Camera.RetrieveImage(), Camera.RetrieveMeasure(), Camera.RetrieveMesh(), Camera.RetrieveObjects(), Camera.RetrieveSVOData(), Camera.SaveAreaMap(), Camera.SaveCurrentDepthInFile(), Camera.SaveCurrentImageInFile(), Camera.SaveCurrentPointCloudInFile(), Camera.SaveMesh(), Camera.SavePointCloud(), Camera.SetCameraSettings(), Camera.SetIMUOrientationPrior(), Camera.SetRegionOfInterest(), Camera.SetSVOPosition(), Camera.StartPublishing(), Camera.StartRegionOfInterestAutoDetection(), Camera.StopPublishing(), Camera.UpdateFusedPointCloud(), Camera.UpdateMesh(), Camera.UpdateObjectsBatch(), and Camera.UpdateSelfCalibration().

Property Documentation

◆ ImageWidth

int ImageWidth
get

Width of the images returned by the camera in pixels.

It corresponds to the camera's current resolution setting.

◆ ImageHeight

int ImageHeight
get

Height of the images returned by the camera in pixels.

It corresponds to the camera's current resolution setting.

◆ Baseline

float Baseline
get

Baseline of the camera (distance between the cameras).

Extracted from calibration files.

Referenced by Camera.GetPosition().

◆ HorizontalFieldOfView

float HorizontalFieldOfView
get

Current horizontal field of view in degrees of the camera.

◆ VerticalFieldOfView

float VerticalFieldOfView
get

Current vertical field of view in degrees of the camera.

◆ SensorsConfiguration

◆ CalibrationParametersRaw

CalibrationParameters CalibrationParametersRaw
get

Stereo parameters for current ZED camera prior to rectification (distorted).

◆ CalibrationParametersRectified

CalibrationParameters CalibrationParametersRectified
get

Stereo parameters for current ZED camera after rectification (undistorted).

◆ CameraModel

sl.MODEL CameraModel
get

Model of the camera.

◆ IsCameraReady

bool IsCameraReady
get

Whether the camera has been successfully initialized.