SL_PositionalTrackingParameters Struct Reference

Structure containing a set of parameters for the positional tracking module initialization. More...

Data Fields

struct SL_Quaternion initial_world_rotation
 Rotation of the camera in the world frame when the camera is started. More...
 
struct SL_Vector3 initial_world_position
 Position of the camera in the world frame when the camera is started. More...
 
bool enable_area_memory
 Whether the camera can remember its surroundings. More...
 
bool enable_pose_smothing
 Whether to enable smooth pose correction for small drift correction. More...
 
bool set_floor_as_origin
 Initializes the tracking to be aligned with the floor plane to better position the camera in space. More...
 
bool set_as_static
 Whether to define the camera as static. More...
 
bool enable_imu_fusion
 Whether to enable the IMU fusion. More...
 
float depth_min_range
 Whether to enable the IMU fusion. More...
 
bool set_gravity_as_origin
 Whether to override 2 of the 3 components from initial_world_rotation using the IMU gravity. More...
 
enum SL_POSITIONAL_TRACKING_MODE mode
 Positional tracking mode used. More...
 

Detailed Description

Structure containing a set of parameters for the positional tracking module initialization.

The default constructor sets all parameters to their default settings.

Note
Parameters can be user adjusted.

Field Documentation

◆ initial_world_rotation

struct SL_Quaternion SL_PositionalTrackingParameters::initial_world_rotation

Rotation of the camera in the world frame when the camera is started.

Default: Identity quaternion

◆ initial_world_position

struct SL_Vector3 SL_PositionalTrackingParameters::initial_world_position

Position of the camera in the world frame when the camera is started.

Default: Null vector

◆ enable_area_memory

bool SL_PositionalTrackingParameters::enable_area_memory

Whether the camera can remember its surroundings.

This helps correct positional tracking drift and can be helpful for positioning different cameras relative to one other in space.
Default: true

Warning
This mode requires more resources to run, but greatly improves tracking accuracy.
We recommend leaving it on by default.

◆ enable_pose_smothing

bool SL_PositionalTrackingParameters::enable_pose_smothing

Whether to enable smooth pose correction for small drift correction.

Default: false

◆ set_floor_as_origin

bool SL_PositionalTrackingParameters::set_floor_as_origin

Initializes the tracking to be aligned with the floor plane to better position the camera in space.

Default: false

Note
This launches floor plane detection in the background until a suitable floor plane is found.
The tracking will start in SL_POSITIONAL_TRACKING_STATE_SEARCHING state.
Warning
This features does not work with SL_MODEL_ZED since it needs an IMU to classify the floor.
The camera needs to look at the floor during initialization for optimum results.

◆ set_as_static

bool SL_PositionalTrackingParameters::set_as_static

Whether to define the camera as static.

If true, it will not move in the environment. This allows you to set its position using initial_world_position and initial_world_rotation.
All ZED SDK functionalities requiring positional tracking will be enabled without additional computation.
sl_get_position() will return the values set as initial_world_position and initial_world_rotation.
Default: false

◆ enable_imu_fusion

bool SL_PositionalTrackingParameters::enable_imu_fusion

Whether to enable the IMU fusion.

When set to false, only the optical odometry will be used.
Default: true

Note
This setting has no impact on the tracking of a camera.
SL_MODEL_ZED does not have an IMU.

◆ depth_min_range

float SL_PositionalTrackingParameters::depth_min_range

Whether to enable the IMU fusion.

When set to false, only the optical odometry will be used.
Default: true

Note
This setting has no impact on the tracking of a camera
SL_MODEL_ZED does not have an IMU.

◆ set_gravity_as_origin

bool SL_PositionalTrackingParameters::set_gravity_as_origin

Whether to override 2 of the 3 components from initial_world_rotation using the IMU gravity.

Default: true

Note
This parameter does nothing on sl.ZED.MODEL since it does not have an IMU.

◆ mode

enum SL_POSITIONAL_TRACKING_MODE SL_PositionalTrackingParameters::mode

Positional tracking mode used.

Can be used to improve accuracy in some types of scene at the cost of longer runtime.
Default: SL_POSITIONAL_TRACKING_MODE_GEN_1