PositionalTrackingParameters Class Reference

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

Functions

PositionalTrackingParameters __cinit__ (self, _init_pos=Transform(), _enable_memory=True, _enable_pose_smoothing=False, _area_path=None, _set_floor_as_origin=False, _enable_imu_fusion=True, _set_as_static=False, _depth_min_range=-1, _set_gravity_as_origin=True, _mode=POSITIONAL_TRACKING_MODE.GEN_1)
 Default constructor. More...
 
bool save (self, str filename)
 Saves the current set of parameters into a file to be reloaded with the load() method. More...
 
bool load (self, str filename)
 Loads a set of parameters from the values contained in a previously saved file. More...
 
Transform initial_world_transform (self, init_pos=Transform())
 Position of the camera in the world frame when the camera is started. More...
 
None set_initial_world_transform (self, Transform value)
 Set the position of the camera in the world frame when the camera is started. More...
 
bool enable_area_memory (self)
 Whether the camera can remember its surroundings. More...
 
bool enable_pose_smoothing (self)
 Whether to enable smooth pose correction for small drift correction. More...
 
bool set_floor_as_origin (self)
 Initializes the tracking to be aligned with the floor plane to better position the camera in space. More...
 
bool enable_imu_fusion (self)
 Whether to enable the IMU fusion. More...
 
str area_file_path (self)
 Path of an area localization file that describes the surroundings (saved from a previous tracking session). More...
 
bool set_as_static (self)
 Whether to define the camera as static. More...
 
float depth_min_range (self)
 Minimum depth used by the ZED SDK for positional tracking. More...
 
bool set_gravity_as_origin (self)
 Whether to override 2 of the 3 rotations from initial_world_transform using the IMU gravity. More...
 
POSITIONAL_TRACKING_MODE mode (self)
 Positional tracking mode used. More...
 

Detailed Description

Class 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 adjusted by the user.

Functions

◆ __cinit__()

PositionalTrackingParameters __cinit__ (   self,
  _init_pos = Transform(),
  _enable_memory = True,
  _enable_pose_smoothing = False,
  _area_path = None,
  _set_floor_as_origin = False,
  _enable_imu_fusion = True,
  _set_as_static = False,
  _depth_min_range = -1,
  _set_gravity_as_origin = True,
  _mode = POSITIONAL_TRACKING_MODE.GEN_1 
)

Default constructor.

Parameters
_init_pos: Chosen initial camera position in the world frame (Transform)
_enable_memory: Activates enable_memory
_enable_pose_smoothing: Activates enable_pose_smoothing
_area_path: Chosen area_path
_set_floor_as_origin: Activates set_floor_as_origin
_enable_imu_fusion: Activates enable_imu_fusion
_set_as_static: Activates set_as_static
_depth_min_range: Activates depth_min_range
_set_gravity_as_origin: Activates set_gravity_as_origin
_mode: Chosen mode
params = sl.PositionalTrackingParameters(init_pos=sl.Transform(), _enable_pose_smoothing=True)

◆ save()

bool save (   self,
str  filename 
)

Saves the current set of parameters into a file to be reloaded with the load() method.

Parameters
filename: Name of the file which will be created to store the parameters.
Returns
True if the file was successfully saved, otherwise False.
Warning
For security reasons, the file must not already exist.
In case a file already exists, the method will return False and existing file will not be updated.

◆ load()

bool load (   self,
str  filename 
)

Loads a set of parameters from the values contained in a previously saved file.

Parameters
filename: Path to the file from which the parameters will be loaded.
Returns
True if the file was successfully loaded, otherwise False.

◆ initial_world_transform()

Transform initial_world_transform (   self,
  init_pos = Transform() 
)

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

Use this sl.Transform to place the camera frame in the world frame.
Default: Identity matrix.

Note
The camera frame (which defines the reference frame for the camera) is by default positioned at the world frame when tracking is started.

◆ set_initial_world_transform()

None set_initial_world_transform (   self,
Transform  value 
)

Set the position of the camera in the world frame when the camera is started.

Parameters
value: Position of the camera in the world frame when the camera will start.

◆ enable_area_memory()

bool enable_area_memory (   self)

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_smoothing()

bool enable_pose_smoothing (   self)

Whether to enable smooth pose correction for small drift correction.

Default: False

◆ set_floor_as_origin()

bool set_floor_as_origin (   self)

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.

◆ enable_imu_fusion()

bool enable_imu_fusion (   self)

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.

◆ area_file_path()

str area_file_path (   self)

Path of an area localization file that describes the surroundings (saved from a previous tracking session).

Default: (empty)

Note
Loading an area file will start a search phase, during which the camera will try to position itself in the previously learned area.
Warning
The area file describes a specific location. If you are using an area file describing a different location, the tracking function will continuously search for a position and may not find a correct one.
The '.area' file can only be used with the same depth mode (sl.DEPTH_MODE) as the one used during area recording.

◆ set_as_static()

bool set_as_static (   self)

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_transform.
All ZED SDK functionalities requiring positional tracking will be enabled without additional computation.
sl.Camera.get_position() will return the value set as initial_world_transform. Default: False

◆ depth_min_range()

float depth_min_range (   self)

Minimum depth used by the ZED SDK for positional tracking.

It may be useful for example if any steady objects are in front of the camera and may perturb the positional tracking algorithm.
Default: -1 (no minimum depth)

◆ set_gravity_as_origin()

bool set_gravity_as_origin (   self)

Whether to override 2 of the 3 rotations from initial_world_transform using the IMU gravity.

Default: True

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

◆ mode()

POSITIONAL_TRACKING_MODE mode (   self)

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