Positional Tracking Settings
The sl::PositionalTrackingParameters structure allows you to customize the behavior of the Positional Tracking module in the ZED SDK. It includes various parameters that can be adjusted to optimize tracking performance based on your specific application requirements.
This section provides an overview of the key parameters available in sl::PositionalTrackingParameters and their recommended usage.
For more information on these parameters, see the API documentation page.
Positional Tracking Mode #
For detailed information about the available positional tracking modes and their capabilities, refer to the Positional Tracking Modes page.
Minimum Depth Range #
📌 Note: Only for positional tracking
GEN_1mode.
Corresponds to the minimum depth used by the ZED SDK for positional tracking.
Setting a minimum depth can help improve tracking stability by ignoring very close static objects (e.g. parts of the robot or mounting rig in the Field of View) that may introduce noise or inaccuracies in the pose estimation.
Default: -1 (no minimum depth)
sl::PositionalTrackingParameters tracking_parameters;
tracking_parameters.mode = sl::POSITIONAL_TRACKING_MODE::GEN_3;
tracking_parameters.depth_min_range = 3.0; // Set the minimum depth perception distance to 3.0m
tracking_parameters = sl.PositionalTrackingParameters()
tracking_parameters.mode = sl.POSITIONAL_TRACKING_MODE.GEN_3
tracking_parameters.depth_min_range = 3.0 # Set the minimum depth perception distance to 3.0m
PositionalTrackingParameters tracking_parameters = new PositionalTrackingParameters();
tracking_parameters.mode = POSITIONAL_TRACKING_MODE.GEN_3;
tracking_parameters.depth_min_range = 3.0; // Set the minimum depth perception distance to 3.0m
Initial World Transform #
Sets the initial pose of the camera in the world frame when positional tracking starts.
This sl::Transform parameter allows you to define how the camera frame is placed in the world frame at the beginning of the positional tracking processing. By default, the camera is aligned with the world.
This parameter is useful when the camera’s position and orientation in the environment are known in advance (e.g., when mounted on a robot with a fixed initial pose). It allows tracking results to be expressed relative to that initial pose, with positions reported in REFERENCE_FRAME::WORLD.
For more information, see the Coordinate Frames page.
Default: Identity matrix.
Recommendations:
- Use when your camera is rigidly mounted and you know its pose relative to your world coordinate system.
- Useful in multi‐camera or multi‐sensor setups to align all sensors to a common reference.
sl::PositionalTrackingParameters params;
params.initial_world_transform = sl::Transform::identity(); // or set a custom pose: sl::Transform(tr, rot);
tracking_parameters.initial_world_transform = sl.Transform.identity() # or set a custom pose: sl.Transform(tr, rot)
tracking_parameters.initial_world_transform = Transform.Identity; // or Transform(tr, rot)
Enable Area Memory #
Allows the camera to remember its surroundings and reuse a saved area map for localization.
If enabled, the positional tracking algorithm builds and retains an area map, enabling loop‐closure, drift correction and re‐localization in previously mapped environments. If disabled, only pure visual‐inertial odometry is used.
Default: true
Recommendations:
- Enable for applications that revisit the same environment (e.g., warehouse robots, AR/VR setups) to benefit from loop-closure and drift correction.
- Disable for short, one-off missions where map building is unnecessary and you want to minimize computational overhead and memory usage.
sl::PositionalTrackingParameters params;
params.enable_area_memory = true;
tracking_parameters = sl.PositionalTrackingParameters()
tracking_parameters.enable_area_memory = True
PositionalTrackingParameters tracking_parameters = new PositionalTrackingParameters();
tracking_parameters.enable_area_memory = true;
Enable Pose Smoothing #
Enables smoothing of the pose to reduce jitter and small fluctuations.
When enabled, the tracker applies a smoothing filter to the pose output, which can reduce small tracking noise, at the expense of a slight delay or responsiveness loss.
Default: false
Recommendations:
- Enable for AR/VR or visualization applications where smooth, jitter-free motion is prioritized over instantaneous responsiveness.
- Disable for high-speed robotics or real-time control applications where minimal latency is critical.
sl::PositionalTrackingParameters params;
params.enable_pose_smoothing = false;
tracking_parameters.enable_pose_smoothing = False
PositionalTrackingParameters tracking_parameters = new PositionalTrackingParameters();
tracking_parameters.enable_pose_smoothing = false;
Set Floor As Origin #
Aligns the tracking coordinate system with the floor plane.
When enabled, the system detects the floor plane at initialization and sets it as the origin (z=0), aligning the world coordinate system with the floor. Tracking remains in SEARCHING_FLOOR_PLANE state until the floor is detected. Requires a camera with IMU support.
Default: false
Recommendations:
- Useful in indoor robotics or AR use‐cases where you assume the floor is the reference plane and you want z=0 at the floor.
- Not suitable for cameras moving in 3D (drones) or when the camera does not see the floor initially.
sl::PositionalTrackingParameters params;
params.set_floor_as_origin = true;
tracking_parameters = sl.PositionalTrackingParameters()
tracking_parameters.set_floor_as_origin = True
PositionalTrackingParameters tracking_parameters = new PositionalTrackingParameters();
tracking_parameters.set_floor_as_origin = true;
Area File Path #
Specifies the path to a previously saved area map file (.area) for relocalization.
When set, the positional tracking system loads the specified area map at startup and attempts to localize the camera within that pre-mapped environment. This enables the camera to immediately recognize its surroundings without rebuilding the map from scratch, resulting in faster initialization and more consistent pose estimation in known environments.
Default: empty string ("")
Recommendations:
- Use this parameter when your application revisits a known environment and you want to enable fast relocalization without rebuilding the map from scratch.
- Ensure the .area file was recorded using the same positional tracking mode and depth mode (for
GEN_1only) as your current configuration. For optimal compatibility and performance, it is recommended to create area maps usingGEN_3mode. See the Positional Tracking Modes page for more details.
sl::PositionalTrackingParameters params;
params.area_file_path = "myEnvironment.area";
tracking_parameters = sl.PositionalTrackingParameters()
tracking_parameters.area_file_path = "/path/to/myEnvironment.area"
PositionalTrackingParameters tracking_parameters = new PositionalTrackingParameters();
tracking_parameters.area_file_path = "myEnvironment.area";
Enable IMU Fusion #
Enables fusion of IMU data with visual odometry for enhanced tracking robustness.
When enabled, the positional tracking system combines IMU measurements (accelerometer and gyroscope) with visual odometry. This fusion significantly improves tracking performance during rapid camera movements, vibrations, or temporary visual occlusions. If disabled, the system relies solely on visual odometry, which may be less robust in challenging motion scenarios.
Default: true
Recommendations:
- Disable only for cameras without IMU (e.g., EOL ZED Model) or for testing pure visual odometry performance.
- Keep enabled on platforms with IMU support for best drift reduction and responsiveness (e.g., ZED 2i, ZED X, ZED X Mini).
sl::PositionalTrackingParameters params;
params.enable_imu_fusion = true;
tracking_parameters = sl.PositionalTrackingParameters()
tracking_parameters.enable_imu_fusion = True
PositionalTrackingParameters tracking_parameters = new PositionalTrackingParameters();
tracking_parameters.enable_imu_fusion = true;
Set As Static #
Treats the camera as stationary, fixing its pose to the initial transform.
When enabled, the camera is assumed to be completely stationary. The pose remains locked to the initial_world_transform value, and all positional tracking computations are skipped. This is useful for fixed-mount scenarios where the camera does not move, but you still need to reference poses in the world frame for other modules (e.g., object detection, spatial mapping).
Default: false
Recommendations:
- Use when the camera is mounted in a fixed location and won’t move (e.g., ceiling rig).
- Not recommended for mobile or robot-mounted cameras.
sl::PositionalTrackingParameters params;
params.set_as_static = true;
tracking_parameters = sl.PositionalTrackingParameters()
tracking_parameters.set_as_static = True
PositionalTrackingParameters tracking_parameters = new PositionalTrackingParameters();
tracking_parameters.set_as_static = true;
Set Gravity As Origin #
Aligns the camera’s orientation with the gravity vector measured by the IMU.
When enabled, the positional tracking system uses the IMU’s gravity vector to override the roll and pitch components of the initial_world_transform, ensuring the camera’s vertical axis aligns with the real-world “up” direction. This guarantees that the world coordinate system’s z-axis points against gravity, regardless of the initial transform’s orientation. The yaw (rotation around the vertical axis) is preserved from the initial transform.
This parameter has no effect on cameras without IMU support (e.g., EOL ZED Model).
Default: true
Recommendations:
- Keep enabled (default) to ensure the world coordinate system aligns with the real-world vertical axis, providing consistent orientation regardless of camera mounting angle.
- Particularly useful for mobile robots, AR/VR applications, and any scenario where maintaining a stable “up” direction is critical for downstream processing.
- Disable only when you need full control over the initial orientation via
initial_world_transformand want to prevent the IMU from overriding roll and pitch values.
sl::PositionalTrackingParameters params;
params.set_gravity_as_origin = true;
tracking_parameters = sl.PositionalTrackingParameters()
tracking_parameters.set_gravity_as_origin = True
PositionalTrackingParameters tracking_parameters = new PositionalTrackingParameters();
tracking_parameters.set_gravity_as_origin = true;
Enable Localization Only #
Enables localization-only mode when using area memory workflows.
When enabled, the positional tracking system localizes the camera within a previously saved area map (.area file) but does not update or expand that map. This mode is useful in deployment scenarios where the environment has been pre-mapped and you want fast, stable relocalization without modifying the stored map data.
This parameter requires enable_area_memory to be true and a valid area_file_path to be set. If no area map is provided, this parameter has no effect.
Default: false
Recommendations:
- Enable for deployment scenarios where the environment has been pre-mapped and you want consistent, fast relocalization without modifying the stored area file (e.g., production robots operating in a fixed warehouse layout).
- Disable during initial mapping sessions to allow the area map to be created or updated as the environment changes.
sl::PositionalTrackingParameters params;
params.enable_localization_only = true; // Localize within an existing .area file without updating it
tracking_parameters = sl.PositionalTrackingParameters()
tracking_parameters.enable_localization_only = True # Localize only, do not update the map
PositionalTrackingParameters tracking_parameters = new PositionalTrackingParameters();
tracking_parameters.enable_localization_only = true; // Localize only, do not update the map
Enable 2D Ground Mode #
Constrains positional tracking to a 2D ground plane, reducing vertical drift for ground-based platforms.
When enabled, the tracker assumes the camera moves primarily on a flat horizontal surface (e.g., a wheeled robot on a floor). This constraint removes the vertical degree of freedom from pose estimation, preventing height drift and improving tracking stability for platforms that do not require full 3D motion tracking.
This mode is specifically designed for ground-based mobile robots, AGVs (Automated Guided Vehicles), and AMRs (Autonomous Mobile Robots) operating on flat surfaces.
Default: false
Recommendations:
- Enable for wheeled robots, AGVs, or AMRs operating on flat surfaces to eliminate vertical drift and improve horizontal tracking accuracy.
- Disable for aerial vehicles (drones), handheld cameras, or multi-floor navigation scenarios that require full 3D pose estimation.
sl::PositionalTrackingParameters params;
params.enable_2d_ground_mode = true; // Constrain tracking to a 2D ground plane
tracking_parameters = sl.PositionalTrackingParameters()
tracking_parameters.enable_2d_ground_mode = True # Enable 2D ground-constrained tracking
PositionalTrackingParameters tracking_parameters = new PositionalTrackingParameters();
tracking_parameters.enable_2d_ground_mode = true; // Enable 2D ground-constrained tracking