Class containing positional tracking data giving the position and orientation of the camera in 3D space. More...
Functions | |
None | init_pose (self, Pose pose) |
Deep copy from another sl.Pose. More... | |
None | init_transform (self, Transform pose_data, timestamp=0, confidence=0) |
Initializes the sl.Pose from a sl.Transform. More... | |
Translation | get_translation (self, py_translation=Translation()) |
Returns the sl.Translation corresponding to the current sl.Pose. More... | |
Orientation | get_orientation (self, py_orientation=Orientation()) |
Returns the sl.Orientation corresponding to the current sl.Pose. More... | |
Rotation | get_rotation_matrix (self, py_rotation=Rotation()) |
Returns the sl.Rotation corresponding to the current sl.Pose. More... | |
np.array[float] | get_rotation_vector (self) |
Returns the the 3x1 rotation vector (obtained from 3x3 rotation matrix using Rodrigues formula) corresponding to the current sl.Pose. More... | |
np.array[float] | get_euler_angles (self, radian=True) |
Converts the rotation component of the sl.Pose into Euler angles. More... | |
bool | valid (self) |
Whether the tracking is activated or not. More... | |
Timestamp | timestamp (self) |
sl.Timestamp of the sl.Pose. More... | |
Transform | pose_data (self, pose_data=Transform()) |
sl.Transform containing the rotation and translation data of the sl.Pose. More... | |
int | pose_confidence (self) |
Confidence/quality of the pose estimation for the target frame. More... | |
np.array[float] | pose_covariance (self) |
6x6 pose covariance matrix (NumPy array) of translation (the first 3 values) and rotation in so3 (the last 3 values). More... | |
np.array[float] | twist (self) |
Twist of the camera available in reference camera. More... | |
np.array[float] | twist_covariance (self) |
Row-major representation of the 6x6 twist covariance matrix of the camera. More... | |
Class containing positional tracking data giving the position and orientation of the camera in 3D space.
Different representations of position and orientation can be retrieved, along with timestamp and pose confidence.
None init_pose | ( | self, | |
Pose | pose | ||
) |
None init_transform | ( | self, | |
Transform | pose_data, | ||
timestamp = 0 , |
|||
confidence = 0 |
|||
) |
Initializes the sl.Pose from a sl.Transform.
pose_data | : sl.Transform containing pose data to copy. |
timestamp | : Timestamp of the pose data. |
confidence | : Confidence of the pose data. |
Translation get_translation | ( | self, | |
py_translation = Translation() |
|||
) |
Returns the sl.Translation corresponding to the current sl.Pose.
py_translation | : sl.Translation to be returned. It creates one by default. |
Orientation get_orientation | ( | self, | |
py_orientation = Orientation() |
|||
) |
Returns the sl.Orientation corresponding to the current sl.Pose.
py_orientation | : sl.Orientation to be returned. It creates one by default. |
Returns the sl.Rotation corresponding to the current sl.Pose.
py_rotation | : sl.Rotation to be returned. It creates one by default. |
np.array[float] get_rotation_vector | ( | self | ) |
Returns the the 3x1 rotation vector (obtained from 3x3 rotation matrix using Rodrigues formula) corresponding to the current sl.Pose.
py_rotation | : sl.Rotation to be returned. It creates one by default. |
np.array[float] get_euler_angles | ( | self, | |
radian = True |
|||
) |
bool valid | ( | self | ) |
Whether the tracking is activated or not.
Timestamp timestamp | ( | self | ) |
sl.Timestamp of the sl.Pose.
This timestamp should be compared with the camera timestamp for synchronization.
Referenced by Timestamp.data_ns(), Timestamp.get_microseconds(), Timestamp.get_milliseconds(), Timestamp.get_nanoseconds(), Timestamp.get_seconds(), Timestamp.set_microseconds(), Timestamp.set_milliseconds(), Timestamp.set_nanoseconds(), and Timestamp.set_seconds().
sl.Transform containing the rotation and translation data of the sl.Pose.
pose_data | : sl.Transform to be returned. It creates one by default. |
Referenced by GeoPose.__cinit__(), and GeoPose.pose_data().
int pose_confidence | ( | self | ) |
Confidence/quality of the pose estimation for the target frame.
A confidence metric of the tracking [0-100] with:
np.array[float] pose_covariance | ( | self | ) |
6x6 pose covariance matrix (NumPy array) of translation (the first 3 values) and rotation in so3 (the last 3 values).
np.array[float] twist | ( | self | ) |
Twist of the camera available in reference camera.
This expresses velocity in free space, broken into its linear and angular parts.
np.array[float] twist_covariance | ( | self | ) |
Row-major representation of the 6x6 twist covariance matrix of the camera.
This expresses the uncertainty of the twist.