Lie¶
SO3¶
Base¶
- class robokit.lie.so3.SO3(so3_like: wp.array, array_type: Literal['warp'], compute_backend: Literal['warp'] | None = ...)[source]¶
- class robokit.lie.so3.SO3(so3_like: torch.Tensor, array_type: Literal['torch'] | None = ..., compute_backend: Literal['torch', 'warp'] | None = ...)
- class robokit.lie.so3.SO3(so3_like: Quaternion | ndarray, array_type: Literal['numpy'] | None = ..., compute_backend: Literal['pinocchio'] | None = ...)
SO(3) representation using quaternions.
Internal parameterization: [qw, qx, qy, qz]. Tangent parameterization: [omega_x, omega_y, omega_z].
- abstract property wxyz: ndarray | torch.Tensor¶
Quaternion part of SO(3) as [qw, qx, qy, qz]
PinocchioSO3¶
- class robokit.lie.pinocchio_so3.PinocchioSO3(so3_like: wp.array, array_type: Literal['warp'], compute_backend: Literal['warp'] | None = ...)[source]¶
- class robokit.lie.pinocchio_so3.PinocchioSO3(so3_like: torch.Tensor, array_type: Literal['torch'] | None = ..., compute_backend: Literal['torch', 'warp'] | None = ...)
- class robokit.lie.pinocchio_so3.PinocchioSO3(so3_like: Quaternion | ndarray, array_type: Literal['numpy'] | None = ..., compute_backend: Literal['pinocchio'] | None = ...)
Pinocchio SO3 backend.
NOTE this backend does not support batching.
- as_matrix() Float[ndarray, '3 3'][source]¶
Convert the SO3 representation to a 3x3 rotation matrix.
Example
>>> so3 = PinocchioSO3(np.array([0.7071, 0.0, 0.0, 0.7071])) >>> expected_matrix = np.array([[0.0, -1.0, 0.0], [1.0, 0.0, 0.0], [0.0, 0.0, 1.0]]) >>> np.allclose(so3.as_matrix(), expected_matrix, atol=1e-4) True
- property wxyz: Float[ndarray, '4']¶
Quaternion part of SO(3) as [qw, qx, qy, qz]
TorchSO3¶
WarpSO3¶
SE3¶
Base¶
- class robokit.lie.se3.SE3(se3_like: wp.array, array_type: Literal['warp'], compute_backend: Literal['warp'] | None = ...)[source]¶
- class robokit.lie.se3.SE3(se3_like: torch.Tensor, array_type: Literal['torch'] | None = ..., compute_backend: Literal['torch', 'warp'] | None = ...)
- class robokit.lie.se3.SE3(se3_like: SE3 | ndarray, array_type: Literal['numpy'] | None = ..., compute_backend: Literal['pinocchio'] | None = ...)
SE(3) representation.
Internal parameterization: [x, y, z, qw, qx, qy, qz]. Tangent parameterization: [vx, vy, vz, omega_x, omega_y, omega_z].
- abstractmethod adjoint() ndarray | torch.Tensor[source]¶
The 6x6 adjoint matrix Ad_T = [[R, skew(t) @ R], [0, R]] mapping twists as v’ = Ad_T @ v with [v, omega] ordering (linear first, then angular).
- abstractmethod log() ndarray | torch.Tensor[source]¶
The log representation in [v, omega] format, linear first, then angular.
- abstract property quat_wxyz: ndarray | torch.Tensor¶
Quaternion part of SE(3) as [qw, qx, qy, qz]
- abstract property xyz: ndarray | torch.Tensor¶
Translation part of SE(3) as [x, y, z]
- abstract property xyz_wxyz: ndarray | torch.Tensor¶
Internal parameterization of SE(3) as [x, y, z, qw, qx, qy, qz]
PinocchioSE3¶
- class robokit.lie.pinocchio_se3.PinocchioSE3(se3_like: SE3 | Float[ndarray, '7'], array_type: Literal['numpy'] | None = None, compute_backend: Literal['pinocchio'] | None = None)[source]¶
Pinocchio SE3 backend.
NOTE this backend does not support batching.
- adjoint() Float[ndarray, '6 6'][source]¶
Compute the 6x6 adjoint representation Ad_T of this SE(3) transform. This matrix maps twists between frames as: v’ = Ad_T @ v.
Convention: twist/log vectors use [v, omega] ordering (linear first, then angular).
Example
>>> # 90-deg rotation about Z (no translation) >>> theta = np.pi / 2 >>> se3 = PinocchioSE3(np.array([0.0, 0.0, 0.0, np.cos(theta/2), 0.0, 0.0, np.sin(theta/2)])) >>> Ad = se3.adjoint() >>> Rz = np.array([[0.0, -1.0, 0.0], ... [1.0, 0.0, 0.0], ... [0.0, 0.0, 1.0]]) >>> Ad_expected = np.block([[Rz, np.zeros((3, 3))], ... [np.zeros((3, 3)), Rz]]) >>> Ad.shape (6, 6) >>> np.allclose(Ad, Ad_expected) True
- static exp(log_transform: Float[ndarray, '6'], array_type: Literal['numpy'] = 'numpy', compute_backend: Literal['pinocchio'] = 'pinocchio') PinocchioSE3[source]¶
Compute the exponential map of the logarithm of the SE(3) transformation. The input is assumed to be in [log_translation, log_rotation] format.
Example
>>> log_se3 = np.array([1.0, 3.92699, 0.785398, 1.570796, 0.0, 0.0]) >>> se3 = PinocchioSE3.exp(log_se3) >>> np.allclose(se3.xyz_wxyz, np.array([1.0, 2.0, 3.0, 0.70710678, 0.70710678, 0.0, 0.0]), atol=1e-6) True
- log() Float[ndarray, '6'][source]¶
Compute the logarithm of the SE(3) transformation. The output is in [v, omega] format (linear first, then angular).
Example
>>> se3 = PinocchioSE3(np.array([1.0, 2.0, 3.0, 0.70710678, 0.70710678, 0.0, 0.0])) >>> log_se3 = se3.log() >>> np.allclose(log_se3, np.array([1.0, 3.92699, 0.785398, 1.570796, 0.0, 0.0]), atol=1e-6) True
- property quat_wxyz: Float[ndarray, '4']¶
Quaternion part of SE(3) as [qw, qx, qy, qz]
- property xyz: Float[ndarray, '3']¶
Translation part of SE(3) as [x, y, z]
- property xyz_wxyz: Float[ndarray, '7']¶
Internal parameterization of SE(3) as [x, y, z, qw, qx, qy, qz]