PositionalTrackingParameters Class Reference

Parameters for positional tracking 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)
 Default constructor. Sets all parameters to their default and optimized values. More...
 
bool save (String filename)
 Saves the current set of parameters into a file. More...
 
bool load (String filename)
 Loads the values of the parameters contained in a file. More...
 
bool operator== (const PositionalTrackingParameters &param1) const
 
bool operator!= (const PositionalTrackingParameters &param1) const
 

Attributes

Transform initial_world_transform
 
bool enable_area_memory
 
bool enable_pose_smoothing
 
bool set_floor_as_origin
 
String area_file_path
 
bool enable_imu_fusion
 
bool set_as_static
 
float depth_min_range
 This setting allows you to change the minimum depth used by the SDK for Positional Tracking. It may be useful for example if any steady objects are in front of the camera and may perturbed the positional tracking algorithm. default : -1 which means no minimum depth. More...
 
bool set_gravity_as_origin
 This setting allows you to override 2 of the 3 rotations from initial_world_transform using the IMU gravity default : true. More...
 

Detailed Description

Parameters for positional tracking initialization.

A default constructor is enabled and set to its default parameters.
You can customize it to fit your application and then save it to create a preset that can be loaded for further executions.

Note
Parameters can be user adjusted.

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 
)

Default constructor. Sets all parameters to their default and optimized values.

Functions

◆ save()

bool save ( String  filename)

Saves the current set of parameters into a file.

Parameters
filename: the 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 reason, the file must not exist. In case a file already exists, Function will return false and existing file will not be updated.

◆ load()

bool load ( String  filename)

Loads the values of the parameters contained in a file.

Parameters
filenamethe path to the file from which the parameters will be loaded.
Returns
true if the file was successfully loaded, 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. By default, it should be identity.
Use this 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

This mode enables the camera to 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

This mode enables smooth pose correction for small drift correction.
default: false

◆ set_floor_as_origin

bool set_floor_as_origin

This mode 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 is in POSITIONAL_TRACKING_STATE::SEARCHING state.
Warning
This features work best with the ZED-M since it needs an IMU to classify the floor. The ZED needs to look at the floor during initialization for optimum results.

◆ area_file_path

String area_file_path

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 (MODE) as the one used during area recording.

◆ enable_imu_fusion

bool enable_imu_fusion

This setting allows you to enable or disable 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 ZED camera; only the ZED Mini uses a built-in IMU.

◆ set_as_static

bool set_as_static

This setting allows you 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 SDK functionalities requiring positional tracking will be enabled without additional computation
Camera::getPosition() will return the value set as initial_world_transform for the PATH, and identity as the POSE.

◆ depth_min_range

float depth_min_range

This setting allows you to change the minimum depth used by the SDK for Positional Tracking. It may be useful for example if any steady objects are in front of the camera and may perturbed the positional tracking algorithm. default : -1 which means no minimum depth.

◆ set_gravity_as_origin

bool set_gravity_as_origin

This setting allows you to override 2 of the 3 rotations from initial_world_transform using the IMU gravity default : true.