This class serves as the primary interface between the camera and the various features provided by the SDK. More...
Functions | |
Camera () | |
Default constructor. More... | |
~Camera () | |
Class destructor. More... | |
ERROR_CODE | open (InitParameters init_parameters=InitParameters()) |
Opens the ZED camera from the provided InitParameters. More... | |
InitParameters | getInitParameters () |
Returns the InitParameters used. More... | |
bool | isOpened () |
Reports if the camera has been successfully opened. More... | |
void | close () |
Close an opened camera. More... | |
ERROR_CODE | grab (RuntimeParameters rt_parameters=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... | |
RuntimeParameters | getRuntimeParameters () |
Returns the RuntimeParameters used. More... | |
CameraInformation | getCameraInformation (Resolution image_size=Resolution(0, 0)) |
Returns the CameraInformation associated the camera being used. More... | |
void | updateSelfCalibration () |
Perform a new self-calibration process. More... | |
CUcontext | getCUDAContext () |
Gets the Camera-created CUDA context for sharing it with other CUDA-capable libraries. More... | |
CUstream | getCUDAStream () |
Gets the Camera-created CUDA stream for sharing it with other CUDA-capable libraries. More... | |
ERROR_CODE | findPlaneAtHit (sl::uint2 coord, sl::Plane &plane, PlaneDetectionParameters parameters=PlaneDetectionParameters()) |
Checks the plane at the given left image coordinates. More... | |
ERROR_CODE | findFloorPlane (sl::Plane &floorPlane, sl::Transform &resetTrackingFloorFrame, float floor_height_prior=INVALID_VALUE, sl::Rotation world_orientation_prior=sl::Matrix3f::zeros(), float floor_height_prior_tolerance=INVALID_VALUE) |
Detect the floor plane of the scene. More... | |
HealthStatus | getHealthStatus () |
Returns HealthStatus. More... | |
Camera (const Camera &)=delete | |
The Camera object cannot be copied. Therfore, its copy constructor is disabled. More... | |
Video | |
ERROR_CODE | retrieveImage (Mat &mat, VIEW view=VIEW::LEFT, MEM type=MEM::CPU, Resolution image_size=Resolution(0, 0)) |
Retrieves images from the camera (or SVO file). More... | |
ERROR_CODE | getCameraSettings (VIDEO_SETTINGS settings, int &setting) |
Returns the current value of the requested camera setting (gain, brightness, hue, exposure, etc.). More... | |
ERROR_CODE | getCameraSettings (VIDEO_SETTINGS settings, int &min_val, int &max_val) |
Fills the current values of the requested settings for VIDEO_SETTINGS that supports two values (min/max). More... | |
ERROR_CODE | getCameraSettings (VIDEO_SETTINGS settings, Rect &roi, sl::SIDE side=sl::SIDE::BOTH) |
Overloaded method for VIDEO_SETTINGS::AEC_AGC_ROI which takes a Rect as parameter. More... | |
ERROR_CODE | setCameraSettings (VIDEO_SETTINGS settings, int value=VIDEO_SETTINGS_VALUE_AUTO) |
Sets the value of the requested camera setting (gain, brightness, hue, exposure, etc.). More... | |
ERROR_CODE | setCameraSettings (VIDEO_SETTINGS settings, int min, int max) |
Sets the value of the requested camera setting that supports two values (min/max). More... | |
ERROR_CODE | setCameraSettings (VIDEO_SETTINGS settings, Rect roi, sl::SIDE side=sl::SIDE::BOTH, bool reset=false) |
Overloaded method for VIDEO_SETTINGS::AEC_AGC_ROI which takes a Rect as parameter. More... | |
ERROR_CODE | getCameraSettingsRange (VIDEO_SETTINGS settings, int &min, int &max) |
Get the range for the specified camera settings VIDEO_SETTINGS as min/max value. More... | |
bool | isCameraSettingSupported (VIDEO_SETTINGS setting) |
Test if the video setting is supported by the camera. More... | |
float | getCurrentFPS () |
Returns the current framerate at which the grab() method is successfully called. More... | |
Timestamp | getTimestamp (sl::TIME_REFERENCE reference_time) |
Returns the timestamp in the requested TIME_REFERENCE. More... | |
unsigned int | getFrameDroppedCount () |
Returns the number of frames dropped since grab() was called for the first time. More... | |
int | getSVOPosition () |
Returns the current playback position in the SVO file. More... | |
int | getSVOPositionAtTimestamp (const sl::Timestamp ×tamp) |
Retrieves the frame index within the SVO file corresponding to the provided timestamp. More... | |
void | setSVOPosition (int frame_number) |
Sets the playback cursor to the desired frame number in the SVO file. More... | |
int | getSVONumberOfFrames () |
Returns the number of frames in the SVO file. More... | |
ERROR_CODE | ingestDataIntoSVO (const sl::SVOData &data) |
Ingest SVOData in a SVO file. More... | |
ERROR_CODE | retrieveSVOData (const std::string &key, std::map< sl::Timestamp, sl::SVOData > &data, sl::Timestamp ts_begin=0, sl::Timestamp ts_end=0) |
Retrieves SVO data from the SVO file at the given channel key and in the given timestamp range. More... | |
std::vector< std::string > | getSVODataKeys () |
Get the external channels that can be retrieved from the SVO file. More... | |
Depth Sensing | |
ERROR_CODE | retrieveMeasure (Mat &mat, MEASURE measure=MEASURE::DEPTH, MEM type=MEM::CPU, Resolution image_size=Resolution(0, 0)) |
Computed measures, like depth, point cloud, or normals, can be retrieved using this method. More... | |
ERROR_CODE | setRegionOfInterest (sl::Mat &roi_mask, std::unordered_set< MODULE > module={MODULE::ALL}) |
Defines a region of interest to focus on for all the SDK, discarding other parts. More... | |
ERROR_CODE | getRegionOfInterest (sl::Mat &roi_mask, sl::Resolution image_size=Resolution(0, 0), MODULE module=MODULE::ALL) |
Get the previously set or computed region of interest. More... | |
ERROR_CODE | startRegionOfInterestAutoDetection (sl::RegionOfInterestParameters roi_param=sl::RegionOfInterestParameters()) |
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... | |
ERROR_CODE | getCurrentMinMaxDepth (float &min, float &max) |
Gets the current range of perceived depth. More... | |
Positional Tracking | |
ERROR_CODE | enablePositionalTracking (PositionalTrackingParameters tracking_parameters=PositionalTrackingParameters()) |
Initializes and starts the positional tracking processes. More... | |
POSITIONAL_TRACKING_STATE | getPosition (Pose &camera_pose, REFERENCE_FRAME reference_frame=REFERENCE_FRAME::WORLD) |
Retrieves the estimated position and orientation of the camera in the specified reference frame. More... | |
sl::PositionalTrackingStatus | getPositionalTrackingStatus () |
Return the current status of positional tracking module. More... | |
ERROR_CODE | saveAreaMap (String area_file_path) |
Saves the current area learning file. The file will contain spatial memory data generated by the tracking. More... | |
AREA_EXPORTING_STATE | getAreaExportState () |
Returns the state of the spatial memory export process. More... | |
ERROR_CODE | resetPositionalTracking (const Transform &path) |
Resets the tracking, and re-initializes the position with the given transformation matrix. More... | |
void | disablePositionalTracking (String area_file_path="") |
Disables the positional tracking. More... | |
bool | isPositionalTrackingEnabled () |
Tells if the tracking module is enabled. More... | |
PositionalTrackingParameters | getPositionalTrackingParameters () |
Returns the PositionalTrackingParameters used. More... | |
ERROR_CODE | getSensorsData (SensorsData &data, TIME_REFERENCE reference_time) |
Retrieves the SensorsData (IMU, magnetometer, barometer) at a specific time reference. More... | |
ERROR_CODE | setIMUPrior (const sl::Transform &transform) |
Set an optional IMU orientation hint that will be used to assist the tracking during the next grab(). More... | |
Spatial Mapping | |
ERROR_CODE | enableSpatialMapping (SpatialMappingParameters spatial_mapping_parameters=SpatialMappingParameters()) |
Initializes and starts the spatial mapping processes. More... | |
SPATIAL_MAPPING_STATE | getSpatialMappingState () |
Returns the current spatial mapping state. More... | |
void | requestSpatialMapAsync () |
Starts the spatial map generation process in a non-blocking thread from the spatial mapping process. More... | |
ERROR_CODE | getSpatialMapRequestStatusAsync () |
Returns the spatial map generation status. More... | |
ERROR_CODE | retrieveSpatialMapAsync (Mesh &mesh) |
Retrieves the current generated spatial map only if SpatialMappingParameters::map_type was set as MESH. More... | |
ERROR_CODE | retrieveSpatialMapAsync (FusedPointCloud &fpc) |
Retrieves the current generated spatial map only if SpatialMappingParameters::map_type was set as FUSED_POINT_CLOUD. More... | |
ERROR_CODE | extractWholeSpatialMap (Mesh &mesh) |
Extract the current spatial map from the spatial mapping process only if SpatialMappingParameters::map_type was set as MESH. More... | |
ERROR_CODE | extractWholeSpatialMap (FusedPointCloud &fpc) |
Extract the current spatial map from the spatial mapping process only if SpatialMappingParameters::map_type was set as FUSED_POINT_CLOUD. More... | |
void | pauseSpatialMapping (bool status) |
Pauses or resumes the spatial mapping processes. More... | |
void | disableSpatialMapping () |
Disables the spatial mapping process. More... | |
SpatialMappingParameters | getSpatialMappingParameters () |
Returns the SpatialMappingParameters used. More... | |
Recording | |
ERROR_CODE | enableRecording (RecordingParameters recording_parameters) |
Creates an SVO file to be filled by enableRecording() and disableRecording(). More... | |
RecordingStatus | getRecordingStatus () |
Get the recording information. 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... | |
RecordingParameters | getRecordingParameters () |
Returns the RecordingParameters used. More... | |
Streaming | |
ERROR_CODE | enableStreaming (StreamingParameters streaming_parameters=StreamingParameters()) |
Creates a streaming pipeline. More... | |
void | disableStreaming () |
Disables the streaming initiated by enableStreaming(). More... | |
bool | isStreamingEnabled () |
Tells if the streaming is running. More... | |
StreamingParameters | getStreamingParameters () |
Returns the StreamingParameters used. More... | |
Object Detection | |
ERROR_CODE | enableObjectDetection (ObjectDetectionParameters object_detection_parameters=ObjectDetectionParameters()) |
Initializes and starts object detection module. More... | |
void | disableObjectDetection (unsigned int instance_id=0, bool force_disable_all_instances=false) |
Disables the Object Detection process. More... | |
ERROR_CODE | ingestCustomBoxObjects (const std::vector< CustomBoxObjectData > &objects_in, const unsigned int instance_id=0) |
Feed the 3D Object tracking method with your own 2D bounding boxes from your own detection algorithm. More... | |
ERROR_CODE | ingestCustomMaskObjects (const std::vector< CustomMaskObjectData > &objects_in, const unsigned int instance_id=0) |
Feed the 3D Object tracking method with your own 2D bounding boxes with masks from your own detection algorithm. More... | |
ERROR_CODE | retrieveObjects (Objects &objects, ObjectDetectionRuntimeParameters parameters=ObjectDetectionRuntimeParameters(), const unsigned int instance_id=0) |
Retrieve objects detected by the object detection module. More... | |
ERROR_CODE | retrieveObjects (Objects &objects, CustomObjectDetectionRuntimeParameters parameters=CustomObjectDetectionRuntimeParameters(), const unsigned int instance_id=0) |
Retrieve objects detected by the object detection module. More... | |
ERROR_CODE | getObjectsBatch (std::vector< sl::ObjectsBatch > &trajectories, unsigned int instance_id=0) |
Get a batch of detected objects. More... | |
bool | isObjectDetectionEnabled (unsigned int instance_id=0) |
Tells if the object detection module is enabled. More... | |
ObjectDetectionParameters | getObjectDetectionParameters (unsigned int instance_id=0) |
Returns the ObjectDetectionParameters used. More... | |
Body Tracking | |
ERROR_CODE | enableBodyTracking (BodyTrackingParameters body_tracking_parameters=BodyTrackingParameters()) |
Initializes and starts body tracking module. More... | |
void | disableBodyTracking (unsigned int instance_id=0, bool force_disable_all_instances=false) |
Disables the body tracking process. More... | |
ERROR_CODE | retrieveBodies (Bodies &bodies, BodyTrackingRuntimeParameters parameters=BodyTrackingRuntimeParameters(), unsigned int instance_id=0) |
Retrieves body tracking data from the body tracking module. More... | |
bool | isBodyTrackingEnabled (unsigned int instance_id=0) |
Tells if the body tracking module is enabled. More... | |
BodyTrackingParameters | getBodyTrackingParameters (unsigned int instance_id=0) |
Returns the BodyTrackingParameters used. More... | |
Fusion | |
ERROR_CODE | startPublishing (CommunicationParameters configuration=CommunicationParameters()) |
Set this camera as a data provider for the Fusion module. More... | |
ERROR_CODE | stopPublishing () |
Set this camera as normal camera (without data providing). Stop to send camera data to fusion. More... | |
CommunicationParameters | getCommunicationParameters () |
Returns the CommunicationParameters used. It corresponds to the structure given as argument to the startPublishing() method. More... | |
Static Functions | |
static String | getSDKVersion () |
Returns the version of the currently installed ZED SDK. More... | |
static void | getSDKVersion (int &major, int &minor, int &patch) |
Returns the version of the currently installed ZED SDK. More... | |
static std::vector< sl::DeviceProperties > | getDeviceList () |
List all the connected devices with their associated information. More... | |
static std::vector< sl::StreamingProperties > | getStreamingDeviceList () |
List all the streaming devices with their associated information. More... | |
static sl::ERROR_CODE | reboot (int sn, bool fullReboot=true) |
Performs a hardware reset of the ZED 2 and the ZED 2i. More... | |
static sl::ERROR_CODE | reboot (sl::INPUT_TYPE inputType) |
Performs a hardware reset of all devices matching the InputType. More... | |
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.
A standard program will use the sl::Camera class like this:
Camera | ( | ) |
Default constructor.
Creates an empty Camera object. The parameters will be set when calling open(init_param) with the desired InitParameters .
A Camera object can be created like this:
or
~Camera | ( | ) |
Class destructor.
The destructor will call the close() function and clear the memory previously allocated by the object.
ERROR_CODE open | ( | InitParameters | init_parameters = InitParameters() | ) |
Opens the ZED camera from the provided InitParameters.
The method will also check the hardware requirements and run a self-calibration.
init_parameters | : A structure containing all the initial parameters. Default: a preset of InitParameters. |
Here is the proper way to call this function:
InitParameters getInitParameters | ( | ) |
Returns the InitParameters used.
It corresponds to the structure given as argument to the open() method.
|
inline |
Reports if the camera has been successfully opened.
It has the same behavior as checking if open() returns ERROR_CODE::SUCCESS.
void close | ( | ) |
Close an opened camera.
If open() has been called, this method will close the connection to the camera (or the SVO file) and free the corresponding memory.
If open() wasn't called or failed, this method won't have any effects.
ERROR_CODE grab | ( | RuntimeParameters | rt_parameters = 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.)
As measures are created in this method, its execution can last a few milliseconds, depending on your parameters and your hardware.
The exact duration will mostly depend on the following parameters:
This method is meant to be called frequently in the main loop of your application.
rt_parameters | : A structure containing all the runtime parameters. Default: a preset of RuntimeParameters. |
RuntimeParameters getRuntimeParameters | ( | ) |
Returns the RuntimeParameters used.
It corresponds to the structure given as argument to the grab() method.
CameraInformation getCameraInformation | ( | Resolution | image_size = Resolution(0, 0) | ) |
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.
image_size | : You can specify a size different from the default image size to get the scaled camera information. Default = (0,0) meaning original image size (given by getCameraInformation().camera_configuration.resolution). |
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 method to update the self-calibration data and get more reliable depth values.
CUcontext getCUDAContext | ( | ) |
Gets the Camera-created CUDA context for sharing it with other CUDA-capable libraries.
This can be useful for sharing GPU memories.
CUstream getCUDAStream | ( | ) |
Gets the Camera-created CUDA stream for sharing it with other CUDA-capable libraries.
ERROR_CODE retrieveImage | ( | Mat & | mat, |
VIEW | view = VIEW::LEFT , |
||
MEM | type = MEM::CPU , |
||
Resolution | image_size = Resolution(0, 0) |
||
) |
Retrieves images from the camera (or SVO file).
Multiple images are available along with a view of various measures for display purposes.
Available images and views are listed here.
As an example, VIEW::DEPTH can be used to get a gray-scale version of the depth map, but the actual depth values can be retrieved using retrieveMeasure().
Pixels
Most VIEW modes output image with 4 channels as BGRA (Blue, Green, Red, Alpha), for more information see enum VIEW
Memory
By default, images are copied from GPU memory to CPU memory (RAM) when this function is called.
If your application can use GPU images, using the type parameter can increase performance by avoiding this copy.
If the provided Mat object is already allocated and matches the requested image format, memory won't be re-allocated.
Image size
By default, images are returned in the resolution provided by getCameraInformation().camera_configuration.resolution.
However, you can request custom resolutions. For example, requesting a smaller image can help you speed up your application.
mat | : The sl::Mat to store the image. The method will create the Mat if necessary at the proper resolution. If already created, it will just update its data (CPU or GPU depending on the MEM type). |
view | : Defines the image you want (see VIEW). Default : VIEW::LEFT. |
type | : Defines on which memory the image should be allocated. Default: MEM::CPU. |
image_size | : If specified, define the resolution of the output sl::Mat. If set to Resolution(0,0), the camera resolution will be taken. Default: (0,0). |
ERROR_CODE getCameraSettings | ( | VIDEO_SETTINGS | settings, |
int & | setting | ||
) |
Returns the current value of the requested camera setting (gain, brightness, hue, exposure, etc.).
Possible values (range) of each setting are available here.
settings | : The requested setting. |
setting | : The setting variable to fill. |
ERROR_CODE getCameraSettings | ( | VIDEO_SETTINGS | settings, |
int & | min_val, | ||
int & | max_val | ||
) |
Fills the current values of the requested settings for VIDEO_SETTINGS that supports two values (min/max).
This method only works with the following VIDEO_SETTINGS:
Possible values (range) of each setting are available here.
settings | : The requested setting. |
min_val | : The setting minimum variable to fill. |
max_val | : The setting maximum variable to fill. |
ERROR_CODE getCameraSettings | ( | VIDEO_SETTINGS | settings, |
Rect & | roi, | ||
sl::SIDE | side = sl::SIDE::BOTH |
||
) |
Overloaded method for VIDEO_SETTINGS::AEC_AGC_ROI which takes a Rect as parameter.
setting | : Must be set at VIDEO_SETTINGS::AEC_AGC_ROI, otherwise the method will have no impact. |
roi | : Roi that will be filled. |
side | : SIDE on which to get the ROI from. |
ERROR_CODE setCameraSettings | ( | VIDEO_SETTINGS | settings, |
int | value = VIDEO_SETTINGS_VALUE_AUTO |
||
) |
Sets the value of the requested camera setting (gain, brightness, hue, exposure, etc.).
This method only applies for VIDEO_SETTINGS that require a single value.
Possible values (range) of each setting are available here.
settings | : The setting to be set. |
value | : The value to set. Default: auto mode |
ERROR_CODE setCameraSettings | ( | VIDEO_SETTINGS | settings, |
int | min, | ||
int | max | ||
) |
Sets the value of the requested camera setting that supports two values (min/max).
This method only works with the following VIDEO_SETTINGS:
Possible values (range) of each setting are available here.
settings | : The setting to be set. |
min | : The minimum value that can be reached (-1 or 0 gives full range). |
max | : The maximum value that can be reached (-1 or 0 gives full range). |
ERROR_CODE setCameraSettings | ( | VIDEO_SETTINGS | settings, |
Rect | roi, | ||
sl::SIDE | side = sl::SIDE::BOTH , |
||
bool | reset = false |
||
) |
Overloaded method for VIDEO_SETTINGS::AEC_AGC_ROI which takes a Rect as parameter.
setting | : Must be set at VIDEO_SETTINGS::AEC_AGC_ROI, otherwise the method will have no impact. |
roi | : Rect that defines the target to be applied for AEC/AGC computation. Must be given according to camera resolution. |
side | : SIDE on which to be applied for AEC/AGC computation. |
reset | : Cancel the manual ROI and reset it to the full image. |
ERROR_CODE getCameraSettingsRange | ( | VIDEO_SETTINGS | settings, |
int & | min, | ||
int & | max | ||
) |
Get the range for the specified camera settings VIDEO_SETTINGS as min/max value.
setting | : Must be set at a valid VIDEO_SETTINGS that accepts a min/max range and available for the current camera model. |
bool isCameraSettingSupported | ( | VIDEO_SETTINGS | setting | ) |
Test if the video setting is supported by the camera.
setting | : The video setting to test |
float getCurrentFPS | ( | ) |
Returns the current framerate at which the grab() method is successfully called.
The returned value is based on the difference of camera timestamps between two successful grab() calls.
Timestamp getTimestamp | ( | sl::TIME_REFERENCE | reference_time | ) |
Returns the timestamp in the requested TIME_REFERENCE.
This function can also be used when playing back an SVO file.
reference_time | : The selected TIME_REFERENCE. |
unsigned int getFrameDroppedCount | ( | ) |
Returns the number of frames dropped since grab() was called for the first time.
A dropped frame corresponds to a frame that never made it to the grab method.
This can happen if two frames were extracted from the camera when grab() is called. The older frame will be dropped so as to always use the latest (which minimizes latency).
int getSVOPosition | ( | ) |
Returns the current playback position in the SVO file.
The position corresponds to the number of frames already read from the SVO file, starting from 0 to n.
Each grab() call increases this value by one (except when using InitParameters::svo_real_time_mode).
int getSVOPositionAtTimestamp | ( | const sl::Timestamp & | timestamp | ) |
Retrieves the frame index within the SVO file corresponding to the provided timestamp.
timestamp | The target timestamp for which the frame index is to be determined. |
void setSVOPosition | ( | int | frame_number | ) |
Sets the playback cursor to the desired frame number in the SVO file.
This method allows you to move around within a played-back SVO file. After calling, the next call to grab() will read the provided frame number.
frame_number | : The number of the desired frame to be decoded. |
int getSVONumberOfFrames | ( | ) |
Returns the number of frames in the SVO file.
ERROR_CODE ingestDataIntoSVO | ( | const sl::SVOData & | data | ) |
Ingest SVOData in a SVO file.
data | : Data to ingest in the SVO file. |
ERROR_CODE retrieveSVOData | ( | const std::string & | key, |
std::map< sl::Timestamp, sl::SVOData > & | data, | ||
sl::Timestamp | ts_begin = 0 , |
||
sl::Timestamp | ts_end = 0 |
||
) |
Retrieves SVO data from the SVO file at the given channel key and in the given timestamp range.
key | : The key of the SVOData that is going to be retrieved. |
data | : The map to be filled with SVOData objects, with timestamps as keys. |
ts_begin | : The beginning of the range. |
ts_end | : The end of the range. |
std::vector<std::string> getSVODataKeys | ( | ) |
Get the external channels that can be retrieved from the SVO file.
ERROR_CODE retrieveMeasure | ( | Mat & | mat, |
MEASURE | measure = MEASURE::DEPTH , |
||
MEM | type = MEM::CPU , |
||
Resolution | image_size = Resolution(0, 0) |
||
) |
Computed measures, like depth, point cloud, or normals, can be retrieved using this method.
Multiple measures are available after a grab() call. A full list is available here.
Memory
By default, images are copied from GPU memory to CPU memory (RAM) when this function is called.
If your application can use GPU images, using the type parameter can increase performance by avoiding this copy.
If the provided Mat object is already allocated and matches the requested image format, memory won't be re-allocated.
Measure size
By default, measures are returned in the resolution provided by .camera_configuration.resolution .
However, custom resolutions can be requested. For example, requesting a smaller measure can help you speed up your application.
mat | : The Mat to store the measure. The method will create the Mat if necessary at the proper resolution. If already created, it will just update its data (CPU or GPU depending on the MEM type). |
measure | : Defines the measure you want (see MEASURE). Default: MEASURE::DEPTH. |
type | : Defines on which memory the image should be allocated. Default: MEM::CPU. |
image_size | : If specified, define the resolution of the output sl::Mat. If set to Resolution(0,0), the camera resolution will be taken. Default: (0,0). |
ERROR_CODE setRegionOfInterest | ( | sl::Mat & | roi_mask, |
std::unordered_set< MODULE > | module = {MODULE::ALL} |
||
) |
Defines a region of interest to focus on for all the SDK, discarding other parts.
roi_mask | 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. |
module | Apply the ROI to a list of SDK module, all by default |
ERROR_CODE getRegionOfInterest | ( | sl::Mat & | roi_mask, |
sl::Resolution | image_size = Resolution(0, 0) , |
||
MODULE | module = MODULE::ALL |
||
) |
Get the previously set or computed region of interest.
roi_mask | The Mat returned |
image_size | The optional size of the returned mask |
module | specify which module to get the ROI |
ERROR_CODE startRegionOfInterestAutoDetection | ( | sl::RegionOfInterestParameters | roi_param = sl::RegionOfInterestParameters() | ) |
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.
roi_param | The RegionOfInterestParameters defining parameters for the detection |
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.
ERROR_CODE getCurrentMinMaxDepth | ( | float & | min, |
float & | max | ||
) |
Gets the current range of perceived depth.
min[out] | : Minimum depth detected (in selected sl::UNIT). |
max[out] | : Maximum depth detected (in selected sl::UNIT). |
ERROR_CODE enablePositionalTracking | ( | PositionalTrackingParameters | tracking_parameters = PositionalTrackingParameters() | ) |
Initializes and starts the positional tracking processes.
This method allows you to enable the position estimation of the SDK. It only has to be called once in the camera's lifetime.
When enabled, the position will be update at each grab() call.
Tracking-specific parameter can be set by providing PositionalTrackingParameters to this method.
tracking_parameters | : A structure containing all the specific parameters for the positional tracking. Default: a preset of PositionalTrackingParameters. |
POSITIONAL_TRACKING_STATE getPosition | ( | Pose & | camera_pose, |
REFERENCE_FRAME | reference_frame = REFERENCE_FRAME::WORLD |
||
) |
Retrieves the estimated position and orientation of the camera in the specified reference frame.
If the tracking has been initialized with PositionalTrackingParameters::enable_area_memory to true (default), this method can return POSITIONAL_TRACKING_STATE::SEARCHING.
This means that the tracking lost its link to the initial referential and is currently trying to relocate the camera. However, it will keep on providing position estimations.
camera_pose[out] | : The pose containing the position of the camera and other information (timestamp, confidence). |
reference_frame[in] | : Defines the reference from which you want the pose to be expressed. Default: REFERENCE_FRAME::WORLD. |
sl::PositionalTrackingStatus getPositionalTrackingStatus | ( | ) |
Return the current status of positional tracking module.
ERROR_CODE saveAreaMap | ( | String | area_file_path | ) |
Saves the current area learning file. The file will contain spatial memory data generated by the tracking.
If the tracking has been initialized with PositionalTrackingParameters::enable_area_memory to true (default), the method allows you to export the spatial memory.
Reloading the exported file in a future session with PositionalTrackingParameters::area_file_path initializes the tracking within the same referential.
This method is asynchronous, and only triggers the file generation. You can use getAreaExportState() to get the export state. The positional tracking keeps running while exporting.
area_file_path | : Path of an '.area' file to save the spatial memory database in. |
AREA_EXPORTING_STATE getAreaExportState | ( | ) |
Returns the state of the spatial memory export process.
As saveAreaMap() only starts the exportation, this method allows you to know when the exportation finished or if it failed.
ERROR_CODE resetPositionalTracking | ( | const Transform & | path | ) |
Resets the tracking, and re-initializes the position with the given transformation matrix.
path | : Position of the camera in the world frame when the method is called. |
void disablePositionalTracking | ( | String | area_file_path = "" | ) |
Disables the positional tracking.
The positional tracking is immediately stopped. If a file path is given, saveAreaMap() will be called asynchronously. See getAreaExportState() to get the exportation state.
If the tracking has been enabled, this function will automatically be called by close() .
area_file_path | : If set, saves the spatial memory into an '.area' file. Default: (empty) area_file_path is the name and path of the database, e.g. path/to/file/myArea1.area". |
bool isPositionalTrackingEnabled | ( | ) |
Tells if the tracking module is enabled.
PositionalTrackingParameters getPositionalTrackingParameters | ( | ) |
Returns the PositionalTrackingParameters used.
It corresponds to the structure given as argument to the enablePositionalTracking() method.
ERROR_CODE getSensorsData | ( | SensorsData & | data, |
TIME_REFERENCE | reference_time | ||
) |
Retrieves the SensorsData (IMU, magnetometer, barometer) at a specific time reference.
The delta time between previous and current values can be calculated using data.imu.timestamp
data[out] | : The SensorsData variable to store the data. |
reference_frame[in] | Defines the reference from which you want the data to be expressed. Default: REFERENCE_FRAME::WORLD. |
ERROR_CODE setIMUPrior | ( | const sl::Transform & | transform | ) |
Set an optional IMU orientation hint that will be used to assist the tracking during the next grab().
This method can be used to assist the positional tracking rotation.
sl::Transform | to be ingested into IMU fusion. Note that only the rotation is used. |
ERROR_CODE enableSpatialMapping | ( | SpatialMappingParameters | spatial_mapping_parameters = SpatialMappingParameters() | ) |
Initializes and starts the spatial mapping processes.
The spatial mapping will create a geometric representation of the scene based on both tracking data and 3D point clouds.
The resulting output can be a Mesh or a FusedPointCloud. It can be be obtained by calling extractWholeSpatialMap() or retrieveSpatialMapAsync(). Note that retrieveSpatialMapAsync() should be called after requestSpatialMapAsync().
spatial_mapping_parameters | : A structure containing all the specific parameters for the spatial mapping. Default: a balanced parameter preset between geometric fidelity and output file size. For more information, see the SpatialMappingParameters documentation. |
SPATIAL_MAPPING_STATE getSpatialMappingState | ( | ) |
Returns the current spatial mapping state.
As the spatial mapping runs asynchronously, this method allows you to get reported errors or status info.
void requestSpatialMapAsync | ( | ) |
Starts the spatial map generation process in a non-blocking thread from the spatial mapping process.
The spatial map generation can take a long time depending on the mapping resolution and covered area. This function will trigger the generation of a mesh without blocking the program.
You can get info about the current generation using getSpatialMapRequestStatusAsync(), and retrieve the mesh using retrieveSpatialMapAsync() .
See enableSpatialMapping() for an example.
ERROR_CODE getSpatialMapRequestStatusAsync | ( | ) |
Returns the spatial map generation status.
This status allows to know if the mesh can be retrieved by calling retrieveSpatialMapAsync .
See enableSpatialMapping() for an example.
ERROR_CODE retrieveSpatialMapAsync | ( | Mesh & | mesh | ) |
Retrieves the current generated spatial map only if SpatialMappingParameters::map_type was set as MESH.
After calling requestSpatialMapAsync(), this method allows you to retrieve the generated mesh.
The mesh will only be available when getSpatialMapRequestStatusAsync() returns ERROR_CODE::SUCCESS.
mesh[out] | : The mesh to be filled with the generated spatial map. |
See enableSpatialMapping() for an example.
ERROR_CODE retrieveSpatialMapAsync | ( | FusedPointCloud & | fpc | ) |
Retrieves the current generated spatial map only if SpatialMappingParameters::map_type was set as FUSED_POINT_CLOUD.
After calling requestSpatialMapAsync(), this method allows you to retrieve the generated fused point cloud.
The fused point cloud will only be available when getSpatialMapRequestStatusAsync() returns ERROR_CODE::SUCCESS.
fpc[out] | : The fused point cloud to be filled with the generated spatial map. |
See enableSpatialMapping() for an example.
ERROR_CODE extractWholeSpatialMap | ( | Mesh & | mesh | ) |
Extract the current spatial map from the spatial mapping process only if SpatialMappingParameters::map_type was set as MESH.
If the object to be filled already contains a previous version of the mesh, only changes will be updated, optimizing performance.
mesh[out] | : The mesh to be filled with the generated spatial map. |
See enableSpatialMapping() for an example.
ERROR_CODE extractWholeSpatialMap | ( | FusedPointCloud & | fpc | ) |
Extract the current spatial map from the spatial mapping process only if SpatialMappingParameters::map_type was set as FUSED_POINT_CLOUD.
If the object to be filled already contains a previous version of the fused point cloud, only changes will be updated, optimizing performance.
fpc[out] | : The fused point cloud to be filled with the generated spatial map. |
See enableSpatialMapping() for an example.
void pauseSpatialMapping | ( | bool | status | ) |
Pauses or resumes the spatial mapping processes.
As spatial mapping runs asynchronously, using this method can pause its computation to free some processing power, and resume it again later.
For example, it can be used to avoid mapping a specific area or to pause the mapping when the camera is static.
status | : If true, the integration is paused. If false, the spatial mapping is resumed. |
void disableSpatialMapping | ( | ) |
Disables the spatial mapping process.
The spatial mapping is immediately stopped.
If the mapping has been enabled, this method will automatically be called by close().
SpatialMappingParameters getSpatialMappingParameters | ( | ) |
Returns the SpatialMappingParameters used.
It corresponds to the structure given as argument to the enableSpatialMapping() method.
ERROR_CODE findPlaneAtHit | ( | sl::uint2 | coord, |
sl::Plane & | plane, | ||
PlaneDetectionParameters | parameters = PlaneDetectionParameters() |
||
) |
Checks the plane at the given left image coordinates.
This method gives the 3D plane corresponding to a given pixel in the latest left image grabbed.
The pixel coordinates are expected to be contained x=[0;width-1] and y=[0;height-1], where width/height are defined by the input resolution.
coord[in] | : The image coordinate. The coordinate must be taken from the full-size image. |
plane[out] | : The detected plane if the method succeeded. |
parameters[in] | : A structure containing all the specific parameters for the plane detection. Default: a preset of PlaneDetectionParameters. |
ERROR_CODE findFloorPlane | ( | sl::Plane & | floorPlane, |
sl::Transform & | resetTrackingFloorFrame, | ||
float | floor_height_prior = INVALID_VALUE , |
||
sl::Rotation | world_orientation_prior = sl::Matrix3f::zeros() , |
||
float | floor_height_prior_tolerance = INVALID_VALUE |
||
) |
Detect the floor plane of the scene.
This method analysis the latest image and depth to estimate the floor plane of the scene.
It expects the floor plane to be visible and bigger than other candidate planes, like a table.
floorPlane[out] | : The detected floor plane if the method succeeded. |
resetTrackingFloorFrame[out] | : The transform to align the tracking with the floor plane. The initial position will then be at ground height, with the axis align with the gravity. The positional tracking needs to be reset/enabled with this transform as a parameter (PositionalTrackingParameters.initial_world_transform). |
floor_height_prior[in] | : Prior set to locate the floor plane depending on the known camera distance to the ground, expressed in the same unit as the ZED. If the prior is too far from the detected floor plane, the method will return ERROR_CODE::PLANE_NOT_FOUND. |
world_orientation_prior[in] | : Prior set to locate the floor plane depending on the known camera orientation to the ground. If the prior is too far from the detected floor plane, the method will return ERROR_CODE::PLANE_NOT_FOUND. |
floor_height_prior_tolerance[in] | : Prior height tolerance, absolute value. |
ERROR_CODE enableRecording | ( | RecordingParameters | recording_parameters | ) |
Creates an SVO file to be filled by enableRecording() and disableRecording().
SVO files are custom video files containing the un-rectified images from the camera along with some meta-data like timestamps or IMU orientation (if applicable).
They can be used to simulate a live ZED and test a sequence with various SDK parameters.
Depending on the application, various compression modes are available. See SVO_COMPRESSION_MODE.
recording_parameters | : A structure containing all the specific parameters for the recording such as filename and compression mode. Default: a reset of RecordingParameters . |
RecordingStatus getRecordingStatus | ( | ) |
Get the recording information.
void pauseRecording | ( | bool | status | ) |
Pauses or resumes the recording.
status | : If true, the recording is paused. If false, the recording is resumed. |
void disableRecording | ( | ) |
Disables the recording initiated by enableRecording() and closes the generated file.
See enableRecording() for an example.
RecordingParameters getRecordingParameters | ( | ) |
Returns the RecordingParameters used.
It corresponds to the structure given as argument to the enableRecording() method.
ERROR_CODE enableStreaming | ( | StreamingParameters | streaming_parameters = StreamingParameters() | ) |
Creates a streaming pipeline.
streaming_parameters | : A structure containing all the specific parameters for the streaming. Default: a reset of StreamingParameters . |
void disableStreaming | ( | ) |
Disables the streaming initiated by enableStreaming().
See enableStreaming() for an example.
bool isStreamingEnabled | ( | ) |
Tells if the streaming is running.
StreamingParameters getStreamingParameters | ( | ) |
Returns the StreamingParameters used.
It corresponds to the structure given as argument to the enableStreaming() method.
ERROR_CODE enableObjectDetection | ( | ObjectDetectionParameters | object_detection_parameters = ObjectDetectionParameters() | ) |
Initializes and starts object detection module.
The object detection module currently supports multiple class of objects with the OBJECT_DETECTION_MODEL::MULTI_CLASS_BOX or OBJECT_DETECTION_MODEL::MULTI_CLASS_BOX_ACCURATE.
The full list of detectable objects is available through OBJECT_CLASS and OBJECT_SUBCLASS.
Detected objects can be retrieved using the retrieveObjects() method.
object_detection_parameters | : A structure containing all the specific parameters for the object detection. Default: a preset of ObjectDetectionParameters. |
void disableObjectDetection | ( | unsigned int | instance_id = 0 , |
bool | force_disable_all_instances = false |
||
) |
Disables the Object Detection process.
The object detection module immediately stops and frees its memory allocations.
instance_id | : Id of the object detection instance. Used when multiple instances of the object detection module are enabled at the same time. |
force_disable_all_instances | : Should disable all instances of the object detection module or just instance_id. |
ERROR_CODE ingestCustomBoxObjects | ( | const std::vector< CustomBoxObjectData > & | objects_in, |
const unsigned int | instance_id = 0 |
||
) |
Feed the 3D Object tracking method with your own 2D bounding boxes from your own detection algorithm.
objects_in | : Vector of CustomBoxObjectData to feed the object detection. |
instance_id | : Id of the object detection instance. Used when multiple instances of the object detection module are enabled at the same time. |
ERROR_CODE ingestCustomMaskObjects | ( | const std::vector< CustomMaskObjectData > & | objects_in, |
const unsigned int | instance_id = 0 |
||
) |
Feed the 3D Object tracking method with your own 2D bounding boxes with masks from your own detection algorithm.
objects_in | : Vector of CustomMaskObjectData to feed the object detection. |
instance_id | : Id of the object detection instance. Used when multiple instances of the object detection module are enabled at the same time. |
ERROR_CODE retrieveObjects | ( | Objects & | objects, |
ObjectDetectionRuntimeParameters | parameters = ObjectDetectionRuntimeParameters() , |
||
const unsigned int | instance_id = 0 |
||
) |
Retrieve objects detected by the object detection module.
This method returns the result of the object detection, whether the module is running synchronously or asynchronously.
It is recommended to keep the same Objects object as the input of all calls to this method. This will enable the identification and tracking of every object detected.
objects | : The detected objects will be saved into this object. If the object already contains data from a previous detection, it will be updated, keeping a unique ID for the same person. |
parameters | : Object detection runtime settings, can be changed at each detection. In async mode, the parameters update is applied on the next iteration. |
instance_id | : Id of the object detection instance. Used when multiple instances of the object detection module are enabled at the same time. |
ERROR_CODE retrieveObjects | ( | Objects & | objects, |
CustomObjectDetectionRuntimeParameters | parameters = CustomObjectDetectionRuntimeParameters() , |
||
const unsigned int | instance_id = 0 |
||
) |
Retrieve objects detected by the object detection module.
This method returns the result of the object detection, whether the module is running synchronously or asynchronously.
It is recommended to keep the same Objects object as the input of all calls to this method. This will enable the identification and tracking of every object detected.
objects | : The detected objects will be saved into this object. If the object already contains data from a previous detection, it will be updated, keeping a unique ID for the same person. |
parameters | : Object detection runtime settings, can be changed at each detection. In async mode, the parameters update is applied on the next iteration. |
instance_id | : Id of the object detection instance. Used when multiple instances of the object detection module are enabled at the same time. |
ERROR_CODE getObjectsBatch | ( | std::vector< sl::ObjectsBatch > & | trajectories, |
unsigned int | instance_id = 0 |
||
) |
Get a batch of detected objects.
trajectories | as a std::vector of sl::ObjectsBatch, that will be filled by the batching queue process. |
instance_id | : Id of the object detection instance. Used when multiple instances of the object detection module are enabled at the same time. |
bool isObjectDetectionEnabled | ( | unsigned int | instance_id = 0 | ) |
Tells if the object detection module is enabled.
ObjectDetectionParameters getObjectDetectionParameters | ( | unsigned int | instance_id = 0 | ) |
Returns the ObjectDetectionParameters used.
It corresponds to the structure given as argument to the enableObjectDetection() method.
ERROR_CODE enableBodyTracking | ( | BodyTrackingParameters | body_tracking_parameters = BodyTrackingParameters() | ) |
Initializes and starts body tracking module.
The body tracking module currently supports multiple classes of human skeleton detection with the BODY_TRACKING_MODEL::HUMAN_BODY_FAST, BODY_TRACKING_MODEL::HUMAN_BODY_MEDIUM and BODY_TRACKING_MODEL::HUMAN_BODY_ACCURATE.
This model only detects humans but provides a full skeleton map for each person.
Detected objects can be retrieved using the retrieveBodies() method.
body_tracking_parameters | : A structure containing all the specific parameters for the object detection. Default: default BodyTrackingParameters. |
void disableBodyTracking | ( | unsigned int | instance_id = 0 , |
bool | force_disable_all_instances = false |
||
) |
Disables the body tracking process.
The body tracking module immediately stops and frees its memory allocations.
instance_id | : Id of the body tracking instance. Used when multiple instances of the body tracking module are enabled at the same time. |
force_disable_all_instances | : Should disable all instances of the tracking module module or just instance_id. |
ERROR_CODE retrieveBodies | ( | Bodies & | bodies, |
BodyTrackingRuntimeParameters | parameters = BodyTrackingRuntimeParameters() , |
||
unsigned int | instance_id = 0 |
||
) |
Retrieves body tracking data from the body tracking module.
This method returns the result of the body tracking, whether the module is running synchronously or asynchronously.
It is recommended to keep the same Bodies object as the input of all calls to this method. This will enable the identification and the tracking of every detected body.
bodies | : The tracked bodies will be saved into this object. If the object already contains data from a previous detection, it will be updated, keeping a unique ID for the same person. |
parameters | : Body tracking runtime settings, can be changed at each detection. In async mode, the parameters update is applied on the next iteration. |
instance_id | : Id of the body tracking instance. Used when multiple instances of the body tracking module are enabled at the same time. |
bool isBodyTrackingEnabled | ( | unsigned int | instance_id = 0 | ) |
Tells if the body tracking module is enabled.
BodyTrackingParameters getBodyTrackingParameters | ( | unsigned int | instance_id = 0 | ) |
Returns the BodyTrackingParameters used.
It corresponds to the structure given as argument to the enableBodyTracking() method.
HealthStatus getHealthStatus | ( | ) |
Returns HealthStatus.
That self diagnostic can be enabled by sl::InitParameters::enable_image_validity_check
ERROR_CODE startPublishing | ( | CommunicationParameters | configuration = CommunicationParameters() | ) |
Set this camera as a data provider for the Fusion module.
Metadata is exchanged with the Fusion.
configuration | : A structure containing all the initial parameters. Default: a preset of CommunicationParameters. |
|
static |
Returns the version of the currently installed ZED SDK.
|
static |
Returns the version of the currently installed ZED SDK.
major | : Major variable of the version filled. |
minor | : Minor variable of the version filled. |
patch | : Patch variable of the version filled. |
|
static |
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.
|
static |
List all the streaming devices with their associated information.
|
static |
Performs a hardware reset of the ZED 2 and the ZED 2i.
sn | : Serial number of the camera to reset, or 0 to reset the first camera detected. |
fullReboot | : Perform a full reboot (sensors and video modules) if true, otherwise only the video module will be rebooted. |
|
static |
Performs a hardware reset of all devices matching the InputType.
inputType | : Input type of the devices to reset. |