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_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... | |
| 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... | |
| bool | enable_localization_only |
| Whether to enable the area mode in localize only mode. | |
| bool | enable_2d_ground_mode |
| Whether to enable the 2D ground mode. | |
Structure containing a set of parameters for the positional tracking module initialization.
The default constructor sets all parameters to their default settings.
| struct SL_Quaternion SL_PositionalTrackingParameters::initial_world_rotation |
Rotation of the camera in the world frame when the camera is started.
Default: Identity quaternion
| struct SL_Vector3 SL_PositionalTrackingParameters::initial_world_position |
Position of the camera in the world frame when the camera is started.
Default: Null vector
| 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
| bool SL_PositionalTrackingParameters::enable_pose_smoothing |
Whether to enable smooth pose correction for small drift correction.
Default: false
| 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
| 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
| 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
| 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
| 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
| 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