Camera Class Reference

This class is the main interface with the camera and the SDK features, such as: video, depth, tracking, mapping, and more. More...

Functions

float GetRequestedCameraFPS ()
 Desired FPS from the ZED camera. This is the maximum FPS for the ZED's current resolution unless a lower setting was specified in Open(). Maximum values are bound by the ZED's output, not system performance. More...
 
 Camera (int id)
 Constructor that creates an empty Camera object; More...
 
ERROR_CODE Open (ref InitParameters initParameters)
 Checks if the ZED camera is plugged in and opens it. More...
 
void Close ()
 Closes the camera. Once destroyed, you need to recreate a camera instance to restart again. More...
 
sl.ERROR_CODE Grab (ref sl.RuntimeParameters runtimeParameters)
 Grabs a new image, rectifies it, and computes the disparity map and (optionally) the depth map. The grabbing function is typically called in the main loop in a separate thread. More...
 
sl.INPUT_TYPE GetInputType ()
 Return the INPUT_TYPE currently used More...
 
CalibrationParameters GetCalibrationParameters (bool raw=false)
 
sl.MODEL GetCameraModel ()
 Gets the ZED camera model (ZED or ZED Mini). More...
 
int GetCameraFirmwareVersion ()
 Gets the ZED's camera firmware version. More...
 
int GetSensorsFirmwareVersion ()
 Gets the ZED's sensors firmware version. More...
 
int GetZEDSerialNumber ()
 Gets the ZED's serial number. More...
 
float GetFOV ()
 Returns the ZED's vertical field of view in radians. More...
 
void UpdateSelfCalibration ()
 Perform a new self calibration process. In some cases, due to temperature changes or strong vibrations, the stereo calibration becomes less accurate. Use this function to update the self-calibration data and get more reliable depth values. More...
 
uint GetFrameDroppedCount ()
 Gets the number of frames dropped since Grab() was called for the first time. Based on camera timestamps and an FPS comparison. More...
 
sl.ERROR_CODE findFloorPlane (ref PlaneData plane, out float playerHeight, Quaternion priorQuat, Vector3 priorTrans)
 Plane Detection ///. More...
 
sl.ERROR_CODE FindFloorPlane (ref PlaneData plane, out float playerHeight, Quaternion priorQuat, Vector3 priorTrans)
 Looks for a plane in the visible area that is likely to represent the floor. Use ZEDPlaneDetectionManager.DetectFloorPlane for a higher-level version that turns planes into GameObjects. 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. These arrays are updated directly from the wrapper. 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. These arrays are updated directly from the wrapper. More...
 
sl.ERROR_CODE findPlaneAtHit (ref PlaneData plane, Vector2 coord)
 Checks for a plane in the real world at given screen-space coordinates. More...
 
sl.ERROR_CODE FindPlaneAtHit (ref PlaneData plane, Vector2 coord)
 Checks for a plane in the real world at given screen-space 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. These arrays are updated directly from the wrapper. 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. These arrays are updated directly from the wrapper. More...
 
sl.ERROR_CODE SaveCurrentImageInFile (sl.VIEW view, String filename)
 Save utils fct ///. More...
 
sl.ERROR_CODE SaveCurrentDepthInFile (SIDE side, String filename)
 Save the current depth in a file defined by filename. Supported formats are PNG,PFM and PGM More...
 
sl.ERROR_CODE SaveCurrentPointCloudInFile (SIDE side, String filename)
 Save the current point cloud in a file defined by filename. Supported formats are PLY,VTK,XYZ and PCD 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 ZEDMat. 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. More...
 
int GetConfidenceThreshold ()
 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. 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...
 
Positional Tracking

Initialize and Start the tracking functions

Parameters
positionalTrackingParametersstruct that contains all positional tracking parameters
Returns
ERROR_CODE.FAILURE if the area_file_path file wasn't found, SUCCESS otherwise.
sl.ERROR_CODE EnablePositionalTracking (ref PositionalTrackingParameters positionalTrackingParameters)
 
void DisablePositionalTracking (string path="")
 Stop the motion tracking, if you want to restart, call enableTracking(). More...
 
bool IsPositionalTrackingEnabled ()
 Gets the current position of the camera and state of the tracking, with an optional offset to the tracking frame. More...
 
ERROR_CODE SaveAreaMap (string areaFilePath)
 Saves the current area learning file. The file will contain spatial memory data generated by the tracking. More...
 
AREA_EXPORT_STATE GetAreaExportState ()
 Returns the state of the spatial memory export process. More...
 
sl.ERROR_CODE ResetPositionalTracking (Quaternion rotation, Vector3 translation)
 Reset tracking More...
 
SensorsConfiguration GetSensorsConfiguration ()
 
CameraInformation GetCameraInformation (Resolution resolution=new Resolution())
 Returns the calibration parameters, serial number and other information about 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 ZED Tracking. 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. A tracking frame defines what part of the ZED is its center for tracking purposes. See ZEDCommon.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 ZED1). 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. More...
 
ERROR_CODE GetIMUOrientation (ref Quaternion rotation, TIME_REFERENCE referenceTime=TIME_REFERENCE.IMAGE)
 Gets the rotation given by the ZED-M/ZED2 IMU. Return an error if using ZED (v1) which does not contains internal sensors More...
 
ERROR_CODE GetSensorsData (ref SensorsData data, TIME_REFERENCE referenceTime=TIME_REFERENCE.IMAGE)
 Gets the full Sensor data from the ZED-M or ZED2 . Return an error if using ZED (v1) which does not contains internal sensors More...
 
ERROR_CODE SetRegionOfInterest (sl.Mat roiMask)
 Defines a region of interest to focus on for all the SDK, discarding other parts. 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 a file for recording the ZED's output into a .SVO or .AVI video. More...
 
ERROR_CODE EnableRecording (RecordingParameters recordingParameters)
 
sl.RecordingStatus GetRecordingStatus ()
 Get the recording information More...
 
sl.RecordingParameters GetRecordingParameters ()
 Get the recording parameters More...
 
void PauseRecording (bool status)
 Pauses or resumes the recording. More...
 
void DisableRecording ()
 Stops recording to an SVO/AVI, if applicable, and closes the 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)
 Streaming Module ///. More...
 
ERROR_CODE EnableStreaming (ref StreamingParameters streamingParameters)
 Creates an streaming pipeline. More...
 
bool IsStreamingEnabled ()
 Tells if streaming is running or not. More...
 
void DisableStreaming ()
 Stops the streaming pipeline. More...
 
sl.StreamingParameters GetStreamingParameters ()
 Get the streaming parameters 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 streaming devices with their associated information. This function lists all the cameras available and provides their serial number, models and other information. More...
 
static sl.StreamingProperties[] GetStreamingDeviceList (out int nbDevices)
 List all the connected devices with their associated information. This function lists all the cameras available and provides their serial number, models and other information. More...
 
static sl.ERROR_CODE Reboot (int serialNumber, bool fullReboot=true)
 Performs an hardware reset of the ZED 2. 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...
 

Attributes

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

Properties

int ImageWidth [get]
 Width of the images returned by the ZED in pixels. Corresponds to the ZED's current resolution setting. More...
 
int ImageHeight [get]
 Height of the images returned by the ZED in pixels. Corresponds to the ZED's current resolution setting. More...
 
float Baseline [get]
 Camera's stereo baseline (distance between the cameras). Extracted from calibration files. More...
 
float HorizontalFieldOfView [get]
 ZED's current horizontal field of view in degrees. More...
 
float VerticalFieldOfView [get]
 ZED's current vertical field of view in degrees. 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]
 Camera model - ZED or ZED Mini. 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 ZEDMat. 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. More...
 
InitParameters GetInitParameters ()
 Returns the init parameters used. Correspond to the structure send when the open() function was called. More...
 
RuntimeParameters GetRuntimeParameters ()
 Returns the runtime parameters used. Correspond to the structure send when the grab() function was called. More...
 
PositionalTrackingParameters GetPositionalTrackingParameters ()
 
void SetCameraSettings (VIDEO_SETTINGS settings, int value)
 Sets a value in the ZED's camera settings. More...
 
int GetCameraSettings (VIDEO_SETTINGS settings)
 Gets the value of a given setting from the ZED camera. More...
 
int SetCameraSettings (VIDEO_SETTINGS settings, SIDE side, Rect roi, bool reset=false)
 Overloaded function for CAMERA_SETTINGS.AEC_AGC_ROI (requires Rect as input) More...
 
int GetCameraSettings (VIDEO_SETTINGS settings, SIDE side, ref Rect roi)
 Overloaded function for CAMERA_SETTINGS.AEC_AGC_ROI (requires Rect as input) 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. This is the closest timestamp you can get from when the image was taken. Must be called after calling grab(). More...
 
ulong GetCurrentTimeStamp ()
 Gets the current timestamp at the time the function is called. Can be compared to the camera timestamp for synchronization, since they have the same reference (the computer's start time). More...
 
int GetSVOPosition ()
 Get the current position of the SVO being recorded to. More...
 
int GetSVONumberOfFrames ()
 Gets the total number of frames in the loaded 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. 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. More...
 
bool IsOpened ()
 Reports if the camera has been successfully opened. More...
 
static sl.Resolution GetResolution (RESOLUTION resolution)
 Get sl.Resolion from a RESOLUTION enum 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 spatial mapping parameters used. Correspond to the structure send when the enableSpatialMapping() function was called. 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, int nbSubmeshMax, Vector2[] uvs, IntPtr textures)
 Retrieves all chunks of the current generated mesh. Call UpdateMesh() before calling this. Vertex and triangle arrays must be at least of the sizes returned by UpdateMesh (nbVertices and nbTriangles). More...
 
sl.ERROR_CODE RetrieveMesh (ref Mesh mesh)
 Retrieves all chunks of the current generated mesh. Call UpdateMesh() before calling this. Vertex and triangle arrays must be at least of the sizes returned by UpdateMesh (nbVertices and nbTriangles). More...
 
sl.ERROR_CODE RetrieveChunks (ref Mesh mesh)
 Retrieve all chunks of the generated mesh.Call UpdateMesh() before calling this. Used for mesh vizualisation. 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. Call UpdateFusedPointCloud() before calling this. Vertex arrays must be at least of the sizes returned by UpdateFusedPointCloud More...
 
ERROR_CODE ExtractWholeSpatialMap ()
 
void RequestSpatialMap ()
 Starts the mesh generation process in a thread that doesn't block the spatial mapping process. ZEDSpatialMappingHelper calls this each time it has finished applying the last mesh update. More...
 
void PauseSpatialMapping (bool status)
 Sets the pause state of the data integration mechanism for the ZED's spatial mapping. More...
 
sl.ERROR_CODE GetMeshRequestStatus ()
 Returns the mesh generation status. Useful for knowing when to update and retrieve the mesh. 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. ZEDSpatialMapping then configures itself as if the loaded mesh was just scanned. 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)
 
SPATIAL_MAPPING_STATE GetSpatialMappingState ()
 Gets the current state of spatial mapping. More...
 
Vector3 GetGravityEstimate ()
 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 the ZED Mini, this isn't required thanks to its IMU. 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. 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). More...
 

Object Detection

sl.ERROR_CODE EnableObjectDetection (ref ObjectDetectionParameters od_params)
 Enable object detection module More...
 
void DisableObjectDetection ()
 Disable object detection module and release the resources. More...
 
sl.ObjectDetectionParameters GetObjectDetectionParameters ()
 Get the object detections parameters More...
 
void PauseObjectDetection (bool status)
 Pause or Unpause the object detection More...
 
sl.ERROR_CODE IngestCustomBoxObjects (List< CustomBoxObjectData > objects_in)
 
sl.ERROR_CODE RetrieveObjects (ref Objects objs, ref ObjectDetectionRuntimeParameters od_params)
 Retrieve object detection data 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. This function need to be called after RetrieveObjects, otherwise trajectories will be empty. If also needs to be called after UpdateOBjectsBatch in order to retrieve the number of batch trajectories. More...
 
static AI_Model_status CheckAIModelStatus (AI_MODELS model, int gpu_id=0)
 Object detection ///. 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 is the main interface with the camera and the SDK features, such as: video, depth, tracking, mapping, and more.

Constructor and Destructor

◆ Camera()

Camera ( int  id)
inline

Constructor that 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 ZED's current resolution unless a lower setting was specified in Open(). Maximum values are bound by the ZED'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

◆ Open()

ERROR_CODE Open ( ref InitParameters  initParameters)
inline

Checks if the ZED camera is plugged in and opens it.

Parameters
initParametersClass with all initialization settings. A newly-instantiated InitParameters will have recommended default values.
Returns
ERROR_CODE: The error code gives information about the internal connection process. If SUCCESS is returned, the camera is ready to use. Every other code indicates an error.

◆ 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

Grabs a new image, rectifies it, and computes the disparity map and (optionally) the depth map. The grabbing function is typically called in the main loop in a separate thread.

For more info, read about the SDK function it calls: https://www.stereolabs.com/docs/api_3.X/classsl_1_1Camera.html#afa3678a18dd574e162977e97d7cbf67b

Parameters
runtimeParametersStruct holding all grab parameters.
Returns
the function returns false if no problem was encountered, true otherwise.

◆ GetInputType()

sl.INPUT_TYPE GetInputType ( )
inline

Return the INPUT_TYPE currently used

Returns

◆ 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 ZEDMat. 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.

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. RetrieveMeasure() calls Camera::retrieveMeasure() in the C++ SDK. For more info, read: https://www.stereolabs.com/docs/api_3.X/classsl_1_1Camera.html#a01dce4f0af6f8959a9c974ffaca656b5

Parameters
matZEDMat 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
Error code indicating if the retrieval was successful, and why it wasn't otherwise.

◆ GetInitParameters()

InitParameters GetInitParameters ( )
inline

Returns the init parameters used. Correspond to the structure send when the open() function was called.

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

◆ GetRuntimeParameters()

RuntimeParameters GetRuntimeParameters ( )
inline

Returns the runtime parameters used. Correspond to the structure send when the grab() function was called.

Returns
RuntimeParameters containing the parameters that defines the behavior of the grab.

◆ GetPositionalTrackingParameters()

PositionalTrackingParameters GetPositionalTrackingParameters ( )
inline

◆ GetResolution()

static sl.Resolution GetResolution ( RESOLUTION  resolution)
inlinestatic

Get sl.Resolion from a RESOLUTION enum

Parameters
resolution
Returns

◆ SetCameraSettings() [1/2]

void SetCameraSettings ( VIDEO_SETTINGS  settings,
int  value 
)
inline

Sets a value in the ZED's camera settings.

Parameters
settingsSetting to be changed (brightness, contrast, gain, exposure, etc.)
valueNew value.
usedefaultTrue to set the settings to their default values.

Referenced by Camera.ResetCameraSettings().

◆ GetCameraSettings() [1/2]

int GetCameraSettings ( VIDEO_SETTINGS  settings)
inline

Gets the value of a given setting from the ZED camera.

Parameters
settingsSetting to be retrieved (brightness, contrast, gain, exposure, etc.)
Returns
The current value for the corresponding setting. Returns -1 if encounters an error.

◆ SetCameraSettings() [2/2]

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

Overloaded function for CAMERA_SETTINGS.AEC_AGC_ROI (requires Rect as input)

Parameters
settingsMust be set to CAMERA_SETTINGS.AEC_AGC_ROI. Otherwise will return -1.
sidedefines left=0 or right=1 or both=2 sensor target
roithe roi defined as a sl.Rect
resetDefines if the target must be reset to full sensor
Returns
ERROR_CODE.SUCCESS if ROI has been applied. Other ERROR_CODE otherwise.

◆ GetCameraSettings() [2/2]

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

Overloaded function for CAMERA_SETTINGS.AEC_AGC_ROI (requires Rect as input)

Parameters
settingsMust be set to CAMERA_SETTINGS.AEC_AGC_ROI. Otherwise will return -1.
sidedefines left=0 or right=1 or both=2 sensor target.
roiRoi that will be filled.
Returns
ERROR_CODE.SUCCESS if ROI has been applied. Other ERROR_CODE otherwise.

◆ 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. 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 function 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

Get the current position of the SVO being recorded to.

Returns
Index of the frame being recorded to.

◆ GetSVONumberOfFrames()

int GetSVONumberOfFrames ( )
inline

Gets the total number of frames in the loaded SVO file.

Returns
Total frames in the SVO file. Returns -1 if the SDK is not reading an 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 ZED is already setup, otherwise false.

◆ GetCalibrationParameters()

CalibrationParameters GetCalibrationParameters ( bool  raw = false)
inline

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

◆ GetCameraModel()

sl.MODEL GetCameraModel ( )
inline

Gets the ZED camera model (ZED or ZED Mini).

Returns
Model of the ZED as sl.MODEL.

Referenced by Camera.Open().

◆ GetCameraFirmwareVersion()

int GetCameraFirmwareVersion ( )
inline

Gets the ZED's camera firmware version.

Returns
Firmware version.

◆ GetSensorsFirmwareVersion()

int GetSensorsFirmwareVersion ( )
inline

Gets the ZED's sensors firmware version.

Returns
Firmware version.

◆ GetZEDSerialNumber()

int GetZEDSerialNumber ( )
inline

Gets the ZED's serial number.

Returns
Serial number

◆ GetFOV()

float GetFOV ( )
inline

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

Returns
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 function to update the self-calibration data and get more reliable depth values.

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.

Parameters
cameraID
Returns

◆ GetFrameDroppedCount()

uint GetFrameDroppedCount ( )
inline

Gets the number of frames dropped since Grab() was called for the first time. Based on camera timestamps and an FPS comparison.

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 streaming devices with their associated information. This function 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 connected devices with their associated information. This function 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 an hardware reset of the ZED 2.

Parameters
serialNumberSerial number of the camera
fullRebootPerform a full reboot (Sensors and Video modules)
Returns
SUCCESS if everything went fine, ERROR_CODE::CAMERA_NOT_DETECTED if no camera was detected, 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 ZEDMat. 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.

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. RetrieveMeasure() calls Camera::retrieveMeasure() in the C++ SDK. For more info, read: https://www.stereolabs.com/docs/api_3.X/classsl_1_1Camera.html#a9e0773c0c14ce5156c1fa2fde501c13e

Parameters
matZEDMat 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
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
SUCCESS if values have been extracted. Other 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

◆ DisablePositionalTracking()

void DisablePositionalTracking ( string  path = "")
inline

Stop the motion tracking, if you want to restart, call enableTracking().

Parameters
pathThe path to save the area file

◆ IsPositionalTrackingEnabled()

bool IsPositionalTrackingEnabled ( )
inline

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

Returns
true 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
path

◆ 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

Reset tracking

Parameters
rotation
translation
Returns

◆ GetSensorsConfiguration()

SensorsConfiguration GetSensorsConfiguration ( )
inline

◆ GetCameraInformation()

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

Returns the calibration parameters, serial number and other information about the camera being used.

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

◆ 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 ZED 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. CAMERA gives movement relative to the last pose. WORLD gives cumulative movements since tracking started.
Returns
State of ZED's Tracking system (off, searching, ok).

◆ 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. CAMERA gives movement relative to the last pose. WORLD gives cumulative movements since tracking started.
Returns
State of ZED's Tracking system (off, searching, ok).

◆ 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 ZED is its center for tracking purposes. See ZEDCommon.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 ZED for tracking purposes (left eye, center, right eye).
referenceFrameReference frame for setting the rotation/position. CAMERA gives movement relative to the last pose. WORLD gives cumulative movements since tracking started.
Returns
State of ZED's Tracking system (off, searching, ok).

◆ 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. CAMERA gives movement relative to the last pose. WORLD gives cumulative movements since tracking started.
Returns
State of ZED's Tracking system (off, searching, ok).

◆ SetIMUOrientationPrior()

ERROR_CODE SetIMUOrientationPrior ( ref Quaternion  rotation)
inline

Sets a prior to the IMU orientation (not for ZED1). 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
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 ZED-M/ZED2 IMU. Return an error if using ZED (v1) which does not contains internal sensors

Returns
Error code status.
Parameters
rotationRotation from the IMU.

◆ GetSensorsData()

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

Gets the full Sensor data from the ZED-M or ZED2 . Return an error if using ZED (v1) which does not contains internal sensors

Returns
Error code status.
Parameters
rotationRotation from the IMU.

◆ SetRegionOfInterest()

ERROR_CODE SetRegionOfInterest ( sl.Mat  roiMask)
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, all pixel set to 0 will be discard. If empty, set all pixels as valid, otherwise should fit the resolution of the current instance and its type should be U8_C1.
Returns

◆ EnableSpatialMapping() [1/2]

sl.ERROR_CODE EnableSpatialMapping ( ref SpatialMappingParameters  spatialMappingParameters)
inline

Initializes and begins the spatial mapping processes.

Parameters
spatialMappingParametersSpatial mapping parameters.
Returns
SUCCES if everything went fine, 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
SUCCES if everything went fine, FAILURE otherwise

◆ GetSpatialMappingParameters()

SpatialMappingParameters GetSpatialMappingParameters ( )
inline

Returns the spatial mapping parameters used. Correspond to the structure send when the enableSpatialMapping() function was called.

Returns
SpatialMappingParameters containing the parameters used for spatial mapping intialization.

◆ 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 submesh.
nbTrianglesInSubmeshesArray of the number of triangles in each submesh.
nbUpdatedSubmeshNumber of updated submeshes.
updatedIndicesList of all submeshes updated since the last update.
nbVerticesTotal number of updated vertices in all submeshes.
nbTrianglesTotal number of updated triangles in all submeshes.
nbSubmeshMaxMaximum number of submeshes that can be handled.
Returns
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
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,
int  nbSubmeshMax,
Vector2[]  uvs,
IntPtr  textures 
)
inline

Retrieves all chunks of the current generated mesh. 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.
nbSubmeshMaxMaximum number of submeshes that can be handled.
Returns
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. 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
Error code indicating if the update was successful, and why it wasn't otherwise.

◆ RetrieveChunks()

sl.ERROR_CODE RetrieveChunks ( ref Mesh  mesh)
inline

Retrieve all chunks of the generated mesh.Call UpdateMesh() before calling this. Used for mesh vizualisation.

Parameters
meshThe mesh to be filled with the generated spatial map.
Returns

◆ 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

◆ 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

◆ UpdateFusedPointCloud()

sl.ERROR_CODE UpdateFusedPointCloud ( ref int  nbVertices)
inline

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

Returns
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. 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
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. return SUCCESS if the mesh is filled and available, otherwise ERROR_CODE.FAILURE. warning This is a blocking function.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 doesn't block the spatial mapping process. ZEDSpatialMappingHelper calls this each time it has finished applying the last mesh update.

◆ PauseSpatialMapping()

void PauseSpatialMapping ( bool  status)
inline

Sets the pause state of the data integration mechanism for the ZED's spatial mapping.

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.

◆ 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.

◆ 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.

◆ 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 submesh.
nbTrianglesInSubmeshesArray of the number of triangles in each submesh.
nbSubmeshesNumber of submeshes.
updatedIndicesList of all submeshes updated since the last update.
nbVerticesTotal number of updated vertices in all submeshes.
nbTrianglesTotal number of updated triangles in all submeshes.
nbSubmeshMaxMaximum number of submeshes that can be handled.
textureSizeArray containing the sizes of all the textures (width, height) if applicable.

◆ 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 submesh.
nbTrianglesInSubmeshesArray of the number of triangles in each submesh.
nbSubmeshesNumber of submeshes.
updatedIndicesList of all submeshes updated since the last update.
nbVerticesTotal number of updated vertices in all submeshes.
nbTrianglesTotal number of updated triangles in all submeshes.
nbSubmeshMaxMaximum number of submeshes that can be handled.
Returns
True if the filtering was successful, false otherwise.

◆ 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
True if the filtering was successful, false otherwise.

◆ 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 submesh.
nbTrianglesInSubmeshesArray of the number of triangles in each submesh.
nbSubmeshesNumber of submeshes.
updatedIndicesList of all submeshes updated since the last update.
nbVerticesTotal number of updated vertices in all submeshes.
nbTrianglesTotal number of updated triangles in all submeshes.
textureSizeVector containing the size of all the texture (width, height).
nbSubmeshMaxMaximum number of submeshes that can be handled.
Returns

◆ ApplyTexture() [2/2]

bool ApplyTexture ( ref Mesh  mesh)
inline

◆ GetSpatialMappingState()

SPATIAL_MAPPING_STATE GetSpatialMappingState ( )
inline

Gets the current state of spatial mapping.

Returns

◆ 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 the ZED Mini, this isn't 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 submesh.
nbTrianglesInSubmeshesArray of the number of triangles in each submesh.
nbSubmeshesNumber of submeshes.
updatedIndicesList of all submeshes updated since the last update.
nbVerticesTotal number of updated vertices in all submeshes.
nbTrianglesTotal number of updated triangles in all submeshes.

◆ findFloorPlane()

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

Plane Detection ///.

Looks for a plane in the visible area that is likely to represent the floor. 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

◆ FindFloorPlane()

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

Looks for a plane in the visible area that is likely to represent the floor. 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

◆ 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

◆ 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

◆ findPlaneAtHit()

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

Checks for a plane in the real world at given screen-space coordinates.

Parameters
planeData on the detected plane.
screenPosPoint on the ZED image to check for a plane.
Returns

◆ FindPlaneAtHit()

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

Checks for a plane in the real world at given screen-space coordinates.

Parameters
planeData on the detected plane.
screenPosPoint on the ZED image to check for a plane.
Returns

◆ 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

◆ 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

◆ 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 a file for recording the ZED's output into a .SVO or .AVI video.

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. Whether it ends with .svo or .avi defines its file type.
compressionModeHow much compression to use
bitrateOverride default bitrate with a custom bitrate (Kbits/s)
target_fpsUse 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 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

◆ GetRecordingStatus()

sl.RecordingStatus GetRecordingStatus ( )
inline

Get the recording information

Returns

◆ GetRecordingParameters()

sl.RecordingParameters GetRecordingParameters ( )
inline

Get the recording parameters

Returns

◆ PauseRecording()

void PauseRecording ( bool  status)
inline

Pauses or resumes the recording.

Parameters
statusif true, the recording is paused. If false, the recording is resumed.
Returns

◆ DisableRecording()

void DisableRecording ( )
inline

Stops recording to an SVO/AVI, if applicable, and closes the file.

◆ 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

Streaming Module ///.

Creates an streaming pipeline.

Returns
An 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.

<params> Streaming parameters: See sl.StreamingParameters for more informations. </params>

Returns
An ERROR_CODE that defines if the streaming pipe was successfully created

◆ IsStreamingEnabled()

bool IsStreamingEnabled ( )
inline

Tells if streaming is running or not.

Returns
false if streaming is not enabled, true if streaming is on

◆ DisableStreaming()

void DisableStreaming ( )
inline

Stops the streaming pipeline.

◆ GetStreamingParameters()

sl.StreamingParameters GetStreamingParameters ( )
inline

Get the streaming parameters

Returns

◆ SaveCurrentImageInFile()

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

Save utils fct ///.

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

Returns
returns an 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
sidedefines left (0) or right (1) depth
filenamefilename must end with .png, .pfm or .pgm
Returns
returns an 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
sidedefines left (0) or right (1) point cloud
filenamefilename must end with .ply, .xyz , .vtk or .pcd
Returns
returns an ERROR_CODE that indicates the type of error

◆ CheckAIModelStatus()

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

Object detection ///.

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

◆ 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

◆ EnableObjectDetection()

sl.ERROR_CODE EnableObjectDetection ( ref ObjectDetectionParameters  od_params)
inline

Enable object detection module

Returns
returns an ERROR_CODE that indicates the type of error

◆ DisableObjectDetection()

void DisableObjectDetection ( )
inline

Disable object detection module and release the resources.

◆ GetObjectDetectionParameters()

sl.ObjectDetectionParameters GetObjectDetectionParameters ( )
inline

Get the object detections parameters

Returns

◆ PauseObjectDetection()

void PauseObjectDetection ( bool  status)
inline

Pause or Unpause the object detection

Parameters
status

◆ IngestCustomBoxObjects()

sl.ERROR_CODE IngestCustomBoxObjects ( List< CustomBoxObjectData objects_in)
inline

◆ RetrieveObjects()

sl.ERROR_CODE RetrieveObjects ( ref Objects  objs,
ref ObjectDetectionRuntimeParameters  od_params 
)
inline

Retrieve object detection data

Parameters
od_paramsObject detection runtime parameters
objFrameObjectsFrameSDK that contains all the detection data
Returns
returns an ERROR_CODE that indicates the type of error

◆ UpdateObjectsBatch()

sl.ERROR_CODE UpdateObjectsBatch ( out int  nbBatches)
inline

Update the batch trajectories and retrieve the number of batches.

Parameters
nbBatchesnumbers of batches
Returns
returns an 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. This function need to be called after RetrieveObjects, otherwise trajectories will be empty. If also needs to be called after UpdateOBjectsBatch in order to retrieve the number of batch trajectories.

To retrieve all the objectsbatches, you need to iterate from 0 to nbBatches (retrieved from UpdateObjectBatches)

Parameters
batch_indexindex of the batch retrieved.
objectsBatchtrajectory that will be filled by the batching queue process
Returns
returns an 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.DisableObjectDetection(), Camera.DisablePositionalTracking(), Camera.DisableRecording(), Camera.DisableSpatialMapping(), Camera.DisableStreaming(), 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.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.GetRecordingParameters(), Camera.GetRecordingStatus(), Camera.GetRuntimeParameters(), Camera.GetSensorsConfiguration(), Camera.GetSensorsData(), Camera.GetSensorsFirmwareVersion(), Camera.GetSpatialMappingParameters(), Camera.GetSpatialMappingState(), Camera.GetStreamingParameters(), Camera.GetSVONumberOfFrames(), Camera.GetSVOPosition(), Camera.GetZEDSerialNumber(), Camera.Grab(), Camera.IngestCustomBoxObjects(), Camera.IsOpened(), Camera.IsPositionalTrackingEnabled(), Camera.IsStreamingEnabled(), Camera.LoadMesh(), Camera.MergeChunks(), Camera.Open(), Camera.PauseObjectDetection(), Camera.PauseRecording(), Camera.PauseSpatialMapping(), Camera.RequestSpatialMap(), Camera.ResetPositionalTracking(), Camera.RetrieveChunks(), Camera.RetrieveFusedPointCloud(), Camera.RetrieveImage(), Camera.RetrieveMeasure(), Camera.RetrieveMesh(), Camera.RetrieveObjects(), Camera.SaveAreaMap(), Camera.SaveCurrentDepthInFile(), Camera.SaveCurrentImageInFile(), Camera.SaveCurrentPointCloudInFile(), Camera.SaveMesh(), Camera.SavePointCloud(), Camera.SetCameraSettings(), Camera.SetIMUOrientationPrior(), Camera.SetRegionOfInterest(), Camera.SetSVOPosition(), Camera.UpdateFusedPointCloud(), Camera.UpdateMesh(), Camera.UpdateObjectsBatch(), and Camera.UpdateSelfCalibration().

Property Documentation

◆ ImageWidth

int ImageWidth
get

Width of the images returned by the ZED in pixels. Corresponds to the ZED's current resolution setting.

◆ ImageHeight

int ImageHeight
get

Height of the images returned by the ZED in pixels. Corresponds to the ZED's current resolution setting.

◆ Baseline

float Baseline
get

Camera's stereo baseline (distance between the cameras). Extracted from calibration files.

Referenced by Camera.GetPosition().

◆ HorizontalFieldOfView

float HorizontalFieldOfView
get

ZED's current horizontal field of view in degrees.

◆ VerticalFieldOfView

float VerticalFieldOfView
get

ZED's current vertical field of view in degrees.

◆ 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

Camera model - ZED or ZED Mini.

◆ IsCameraReady

bool IsCameraReady
get

Whether the camera has been successfully initialized.