PositionalTrackingSensorsParameters Struct Reference

Attributes

BatchedData< Transforminitial_world_transforms
 Position of the camera in the world frame when the camera is started. More...
 
bool enable_area_memory = true
 Whether the camera can remember its surroundings. More...
 
bool enable_pose_smoothing = false
 Whether to enable smooth pose correction for small drift correction. More...
 
bool set_floor_as_origin = false
 Initializes the tracking to be aligned with the floor plane to better position the camera in space. More...
 
String area_file_path = String()
 Path of an area localization file that describes the surroundings (saved from a previous tracking session). More...
 
bool enable_imu_fusion = true
 Whether to enable the IMU fusion. More...
 
bool set_as_static = false
 Whether to define the camera as static. More...
 
float depth_min_range = -1.f
 Minimum depth used by the ZED SDK for positional tracking. More...
 
bool set_gravity_as_origin = true
 Whether to override 2 of the 3 rotations from initial_world_transforms using the IMU gravity. More...
 
POSITIONAL_TRACKING_MODE mode = POSITIONAL_TRACKING_MODE::GEN_1
 Positional tracking mode used. More...
 
bool enable_GNSS_fusion = false
 This attribute is responsible for enabling or not GNSS positional tracking fusion. More...
 
GNSSCalibrationParameters gnss_calibration_parameters
 Control the VIO / GNSS calibration process. More...
 
Transform base_footprint_to_world_transform
 Position and orientation of the base footprint with respect to the user world. This transform represents a basis change from Base footprint coordinate frame to user world coordinate frame. More...
 
Transform base_footprint_to_baselink_transform
 Position and orientation of the base footprint with respect to the baselink. This transform represents a basis change from base footprint coordinate frame to baselink coordinate frame. More...
 
SensorDeviceIdentifier tracking_camera_id
 ID of the camera used for positional tracking. If not specified, will use the first camera called with the subscribe() method. More...
 

Variables

◆ initial_world_transforms

BatchedData<Transform> initial_world_transforms

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

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

Whether to enable smooth pose correction for small drift correction.

Default: false

◆ set_floor_as_origin

bool set_floor_as_origin = false

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 feature 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 = String()

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

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

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

◆ depth_min_range

float depth_min_range = -1.f

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

Whether to override 2 of the 3 rotations from initial_world_transforms 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_GNSS_fusion

bool enable_GNSS_fusion = false

This attribute is responsible for enabling or not GNSS positional tracking fusion.

◆ gnss_calibration_parameters

GNSSCalibrationParameters gnss_calibration_parameters

Control the VIO / GNSS calibration process.

◆ base_footprint_to_world_transform

Transform base_footprint_to_world_transform

Position and orientation of the base footprint with respect to the user world. This transform represents a basis change from Base footprint coordinate frame to user world coordinate frame.

Note
Base footprint is the coordinate frame attached to the projected baselink coordinate frame on the ground. It is generally a constant offset between baselink and the ground. Fusion uses the base footprint coordinate frame to determine where is the ground with respect to the tracked baselink position and orientation. baselink is the root coordinate frame of the robot. Fusion configuration file must give the position and orientation of each camera with respect to the baselink

◆ base_footprint_to_baselink_transform

Transform base_footprint_to_baselink_transform

Position and orientation of the base footprint with respect to the baselink. This transform represents a basis change from base footprint coordinate frame to baselink coordinate frame.

Note
This transform is used by the Fusion to determine where is the ground with respect to the baselink coordinate frame which is the root coordinate frame of Fusion.

◆ tracking_camera_id

SensorDeviceIdentifier tracking_camera_id

ID of the camera used for positional tracking. If not specified, will use the first camera called with the subscribe() method.