Class containing a set of parameters for the positional tracking module initialization. More...
Functions | |
PositionalTrackingParameters | __cinit__ (self, _init_pos=Transform(), _enable_memory=True, _enable_pose_smoothing=False, _area_path=None, _set_floor_as_origin=False, _enable_imu_fusion=True, _set_as_static=False, _depth_min_range=-1, _set_gravity_as_origin=True, _mode=POSITIONAL_TRACKING_MODE.GEN_1) |
Default constructor. More... | |
bool | save (self, str filename) |
Saves the current set of parameters into a file to be reloaded with the load() method. More... | |
bool | load (self, str filename) |
Loads a set of parameters from the values contained in a previously saved file. More... | |
Transform | initial_world_transform (self, init_pos=Transform()) |
Position of the camera in the world frame when the camera is started. More... | |
None | set_initial_world_transform (self, Transform value) |
Set the position of the camera in the world frame when the camera is started. More... | |
bool | enable_area_memory (self) |
Whether the camera can remember its surroundings. More... | |
bool | enable_pose_smoothing (self) |
Whether to enable smooth pose correction for small drift correction. More... | |
bool | set_floor_as_origin (self) |
Initializes the tracking to be aligned with the floor plane to better position the camera in space. More... | |
bool | enable_imu_fusion (self) |
Whether to enable the IMU fusion. More... | |
str | area_file_path (self) |
Path of an area localization file that describes the surroundings (saved from a previous tracking session). More... | |
bool | set_as_static (self) |
Whether to define the camera as static. More... | |
float | depth_min_range (self) |
Minimum depth used by the ZED SDK for positional tracking. More... | |
bool | set_gravity_as_origin (self) |
Whether to override 2 of the 3 rotations from initial_world_transform using the IMU gravity. More... | |
POSITIONAL_TRACKING_MODE | mode (self) |
Positional tracking mode used. More... | |
Class containing a set of parameters for the positional tracking module initialization.
The default constructor sets all parameters to their default settings.
PositionalTrackingParameters __cinit__ | ( | self, | |
_init_pos = Transform() , |
|||
_enable_memory = True , |
|||
_enable_pose_smoothing = False , |
|||
_area_path = None , |
|||
_set_floor_as_origin = False , |
|||
_enable_imu_fusion = True , |
|||
_set_as_static = False , |
|||
_depth_min_range = -1 , |
|||
_set_gravity_as_origin = True , |
|||
_mode = POSITIONAL_TRACKING_MODE.GEN_1 |
|||
) |
Default constructor.
_init_pos | : Chosen initial camera position in the world frame (Transform) |
_enable_memory | : Activates enable_memory |
_enable_pose_smoothing | : Activates enable_pose_smoothing |
_area_path | : Chosen area_path |
_set_floor_as_origin | : Activates set_floor_as_origin |
_enable_imu_fusion | : Activates enable_imu_fusion |
_set_as_static | : Activates set_as_static |
_depth_min_range | : Activates depth_min_range |
_set_gravity_as_origin | : Activates set_gravity_as_origin |
_mode | : Chosen mode |
bool save | ( | self, | |
str | filename | ||
) |
Saves the current set of parameters into a file to be reloaded with the load() method.
filename | : Name of the file which will be created to store the parameters. |
bool load | ( | self, | |
str | filename | ||
) |
Loads a set of parameters from the values contained in a previously saved file.
filename | : Path to the file from which the parameters will be loaded. |
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.
None set_initial_world_transform | ( | self, | |
Transform | value | ||
) |
Set the position of the camera in the world frame when the camera is started.
value | : Position of the camera in the world frame when the camera will start. |
bool enable_area_memory | ( | self | ) |
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 enable_pose_smoothing | ( | self | ) |
Whether to enable smooth pose correction for small drift correction.
Default: False
bool set_floor_as_origin | ( | self | ) |
Initializes the tracking to be aligned with the floor plane to better position the camera in space.
Default: False
bool enable_imu_fusion | ( | self | ) |
Whether to enable the IMU fusion.
When set to False, only the optical odometry will be used.
Default: True
str area_file_path | ( | self | ) |
Path of an area localization file that describes the surroundings (saved from a previous tracking session).
Default: (empty)
bool set_as_static | ( | self | ) |
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.get_position() will return the value set as initial_world_transform. Default: False
float depth_min_range | ( | self | ) |
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)
bool set_gravity_as_origin | ( | self | ) |
Whether to override 2 of the 3 rotations from initial_world_transform using the IMU gravity.
Default: True
POSITIONAL_TRACKING_MODE mode | ( | self | ) |
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