PositionalTrackingParameters Class Reference

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

Functions

 PositionalTrackingParameters (Transform init_position_=Transform(), bool enable_memory_=true, bool enable_pose_smoothing_=false, String area_path_=String(), bool set_floor_as_origin_=false, bool enable_imu_fusion_=true, bool set_as_static_=false, float depth_min_range=-1.f, bool set_gravity_as_origin_=true, POSITIONAL_TRACKING_MODE mode=POSITIONAL_TRACKING_MODE::GEN_1)
 Default constructor. More...
 
bool save (String filename, SERIALIZATION_FORMAT format=SERIALIZATION_FORMAT::LEGACY) const
 Saves the current set of parameters into a file to be reloaded with the load() method. More...
 
bool load (String filename, SERIALIZATION_FORMAT format=SERIALIZATION_FORMAT::AUTO)
 Loads a set of parameters from the values contained in a previously saved file. More...
 
bool encode (String &serialized_content, SERIALIZATION_FORMAT format=SERIALIZATION_FORMAT::JSON) const
 Generate a JSON Object (with the struct type as a key) containing the serialized struct, converted into a string. More...
 
bool decode (const String &serialized_content, SERIALIZATION_FORMAT format=SERIALIZATION_FORMAT::JSON)
 Fill the structure from the serialized json object contained in the input string. More...
 
bool operator== (const PositionalTrackingParameters &param1) const
 
bool operator!= (const PositionalTrackingParameters &param1) const
 

Attributes

Transform initial_world_transform
 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_smoothing
 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...
 
String area_file_path
 Path of an area localization file that describes the surroundings (saved from a previous tracking session). More...
 
bool enable_imu_fusion
 Whether to enable the IMU fusion. More...
 
bool set_as_static
 Whether to define the camera as static. More...
 
float depth_min_range
 Minimum depth used by the ZED SDK for positional tracking. More...
 
bool set_gravity_as_origin
 Whether to override 2 of the 3 rotations from initial_world_transform using the IMU gravity. More...
 
POSITIONAL_TRACKING_MODE mode
 Positional tracking mode used. More...
 
bool enable_light_computation_mode = false
 Should enable light computation mode. More...
 

Detailed Description

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

Note
Parameters can be adjusted by the user.

Constructor and Destructor

◆ PositionalTrackingParameters()

PositionalTrackingParameters ( Transform  init_position_ = Transform(),
bool  enable_memory_ = true,
bool  enable_pose_smoothing_ = false,
String  area_path_ = String(),
bool  set_floor_as_origin_ = false,
bool  enable_imu_fusion_ = true,
bool  set_as_static_ = false,
float  depth_min_range = -1.f,
bool  set_gravity_as_origin_ = true,
POSITIONAL_TRACKING_MODE  mode = POSITIONAL_TRACKING_MODE::GEN_1 
)

Default constructor.

Sets all parameters to their default and optimized values.

Functions

◆ save()

bool save ( String  filename,
SERIALIZATION_FORMAT  format = SERIALIZATION_FORMAT::LEGACY 
) const

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 (extension '.yml' will be added if not set).
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 ( String  filename,
SERIALIZATION_FORMAT  format = SERIALIZATION_FORMAT::AUTO 
)

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 (extension '.yml' will be added at the end of the filename if not detected).
Returns
True if the file was successfully loaded, otherwise false.

◆ encode()

bool encode ( String serialized_content,
SERIALIZATION_FORMAT  format = SERIALIZATION_FORMAT::JSON 
) const

Generate a JSON Object (with the struct type as a key) containing the serialized struct, converted into a string.

Parameters
serialized_contentoutput string containing the JSON Object
formatserialization format, default is JSON
Returns
True if file was successfully saved, otherwise false.

◆ decode()

bool decode ( const String serialized_content,
SERIALIZATION_FORMAT  format = SERIALIZATION_FORMAT::JSON 
)

Fill the structure from the serialized json object contained in the input string.

Parameters
serialized_contentinput string containing the JSON Object
formatserialization format, default is JSON
Returns
True if the decoding was successful, otherwise false.

◆ operator==()

bool operator== ( const PositionalTrackingParameters param1) const

Comparison operator ==

Parameters
PositionalTrackingParametersto compare
Returns
true if the two struct are identical

◆ operator!=()

bool operator!= ( const PositionalTrackingParameters param1) const

Comparison operator !=

Parameters
PositionalTrackingParametersto compare
Returns
true if the two struct are different

Variables

◆ initial_world_transform

Transform initial_world_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.

◆ enable_area_memory

bool 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_smoothing

bool enable_pose_smoothing

Whether to enable smooth pose correction for small drift correction.

Default: false

◆ set_floor_as_origin

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

◆ area_file_path

String area_file_path

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.

◆ enable_imu_fusion

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

◆ set_as_static

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

◆ depth_min_range

float depth_min_range

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

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

◆ enable_light_computation_mode

bool enable_light_computation_mode = false

Should enable light computation mode.

If enabled the tracking will just run the part needed by Fusion and nothing more. This parameter will degrade accuracy if positional tracking module is used alone without Fusion. This parameter works only with GEN_2 module.