Transforms¶
Lie group interface for rigid transforms, ported from jaxlie. Used by viser internally and in examples.
Implements SO(2), SO(3), SE(2), and SE(3) Lie groups. Rotations are parameterized via S^1 and S^3.
- class viser.transforms.MatrixLieGroup[source]¶
Bases:
ABC
Interface definition for matrix Lie groups.
- classmethod __init_subclass__(matrix_dim: int = 0, parameters_dim: int = 0, tangent_dim: int = 0, space_dim: int = 0) None [source]¶
Set class properties for subclasses. We default to dummy values.
- __matmul__(other: Self) Self [source]¶
- __matmul__(other: ndarray[tuple[int, ...], dtype[floating]]) ndarray[tuple[int, ...], dtype[floating]]
Overload for the @ operator.
Switches between the group action (.apply()) and multiplication (.multiply()) based on the type of other.
- abstract classmethod identity(batch_axes: ~typing.Tuple[int, ...] = (), dtype: ~numpy.dtype[~typing.Any] | None | type[~typing.Any] | ~numpy._typing._dtype_like._SupportsDType[~numpy.dtype[~typing.Any]] | str | tuple[~typing.Any, int] | tuple[~typing.Any, ~typing.SupportsIndex | ~collections.abc.Sequence[~typing.SupportsIndex]] | list[~typing.Any] | ~numpy._typing._dtype_like._DTypeDict | tuple[~typing.Any, ~typing.Any] = <class 'numpy.float64'>) Self [source]¶
Returns identity element.
- Parameters:
- Returns:
Identity element.
- Return type:
Self
- abstract classmethod from_matrix(matrix: ndarray[tuple[int, ...], dtype[floating]]) Self [source]¶
Get group member from matrix representation.
- abstract as_matrix() ndarray[tuple[int, ...], dtype[floating]] [source]¶
Get transformation as a matrix. Homogeneous for SE groups.
- abstract parameters() ndarray[tuple[int, ...], dtype[floating]] [source]¶
Get underlying representation.
- abstract apply(target: ndarray[tuple[int, ...], dtype[floating]]) ndarray[tuple[int, ...], dtype[floating]] [source]¶
Applies group action to a point.
- abstract multiply(other: Self) Self [source]¶
Composes this transformation with another.
- Returns:
self @ other
- Parameters:
other (Self)
- Return type:
Self
- abstract classmethod exp(tangent: ndarray[tuple[int, ...], dtype[floating]]) Self [source]¶
Computes expm(wedge(tangent)).
- abstract log() ndarray[tuple[int, ...], dtype[floating]] [source]¶
Computes vee(logm(transformation matrix)).
- abstract adjoint() ndarray[tuple[int, ...], dtype[floating]] [source]¶
Computes the adjoint, which transforms tangent vectors between tangent spaces.
More precisely, for a transform GroupType:
` GroupType @ exp(omega) = exp(Adj_T @ omega) @ GroupType `
In robotics, typically used for transforming twists, wrenches, and Jacobians across different reference frames.
- abstract inverse() Self [source]¶
Computes the inverse of our transform.
- Returns:
Output.
- Return type:
Self
- abstract normalize() Self [source]¶
Normalize/projects values and returns.
- Returns:
Normalized group member.
- Return type:
Self
- abstract classmethod sample_uniform(rng: ~numpy.random._generator.Generator, batch_axes: ~typing.Tuple[int, ...] = (), dtype: ~numpy.dtype[~typing.Any] | None | type[~typing.Any] | ~numpy._typing._dtype_like._SupportsDType[~numpy.dtype[~typing.Any]] | str | tuple[~typing.Any, int] | tuple[~typing.Any, ~typing.SupportsIndex | ~collections.abc.Sequence[~typing.SupportsIndex]] | list[~typing.Any] | ~numpy._typing._dtype_like._DTypeDict | tuple[~typing.Any, ~typing.Any] = <class 'numpy.float64'>) Self [source]¶
Draw a uniform sample from the group. Translations (if applicable) are in the range [-1, 1].
- Parameters:
rng (Generator) – numpy generator object.
batch_axes (Tuple[int, ...]) – Any leading batch axes for the output transforms. Each sampled transform will be different.
dtype (dtype[Any] | None | type[Any] | _SupportsDType[dtype[Any]] | str | tuple[Any, int] | tuple[Any, SupportsIndex | Sequence[SupportsIndex]] | list[Any] | _DTypeDict | tuple[Any, Any])
- Returns:
Sampled group member.
- Return type:
Self
- class viser.transforms.SEBase[source]¶
Bases:
Generic
[ContainedSOType
],MatrixLieGroup
Base class for special Euclidean groups.
Each SE(N) group member contains an SO(N) rotation, as well as an N-dimensional translation vector.
- abstract classmethod from_rotation_and_translation(rotation: ContainedSOType, translation: ndarray[tuple[int, ...], dtype[floating]]) Self [source]¶
Construct a rigid transform from a rotation and a translation.
- classmethod from_rotation(rotation: ContainedSOType) Self [source]¶
- Parameters:
rotation (ContainedSOType)
- Return type:
Self
- __matmul__(other: Self | ndarray[tuple[int, ...], dtype[floating]]) Self | ndarray[tuple[int, ...], dtype[floating]] ¶
Overload for the @ operator.
Switches between the group action (.apply()) and multiplication (.multiply()) based on the type of other.
- abstract adjoint() ndarray[tuple[int, ...], dtype[floating]] ¶
Computes the adjoint, which transforms tangent vectors between tangent spaces.
More precisely, for a transform GroupType:
` GroupType @ exp(omega) = exp(Adj_T @ omega) @ GroupType `
In robotics, typically used for transforming twists, wrenches, and Jacobians across different reference frames.
- abstract as_matrix() ndarray[tuple[int, ...], dtype[floating]] ¶
Get transformation as a matrix. Homogeneous for SE groups.
- abstract classmethod exp(tangent: ndarray[tuple[int, ...], dtype[floating]]) Self ¶
Computes expm(wedge(tangent)).
- abstract classmethod from_matrix(matrix: ndarray[tuple[int, ...], dtype[floating]]) Self ¶
Get group member from matrix representation.
- get_batch_axes() Tuple[int, ...] ¶
Return any leading batch axes in contained parameters. If an array of shape (100, 4) is placed in the wxyz field of an SO3 object, for example, this will return (100,).
- abstract classmethod identity(batch_axes: ~typing.Tuple[int, ...] = (), dtype: ~numpy.dtype[~typing.Any] | None | type[~typing.Any] | ~numpy._typing._dtype_like._SupportsDType[~numpy.dtype[~typing.Any]] | str | tuple[~typing.Any, int] | tuple[~typing.Any, ~typing.SupportsIndex | ~collections.abc.Sequence[~typing.SupportsIndex]] | list[~typing.Any] | ~numpy._typing._dtype_like._DTypeDict | tuple[~typing.Any, ~typing.Any] = <class 'numpy.float64'>) Self ¶
Returns identity element.
- Parameters:
- Returns:
Identity element.
- Return type:
Self
- abstract log() ndarray[tuple[int, ...], dtype[floating]] ¶
Computes vee(logm(transformation matrix)).
- abstract rotation() ContainedSOType [source]¶
Returns a transform’s rotation term.
- Return type:
ContainedSOType
- abstract classmethod sample_uniform(rng: ~numpy.random._generator.Generator, batch_axes: ~typing.Tuple[int, ...] = (), dtype: ~numpy.dtype[~typing.Any] | None | type[~typing.Any] | ~numpy._typing._dtype_like._SupportsDType[~numpy.dtype[~typing.Any]] | str | tuple[~typing.Any, int] | tuple[~typing.Any, ~typing.SupportsIndex | ~collections.abc.Sequence[~typing.SupportsIndex]] | list[~typing.Any] | ~numpy._typing._dtype_like._DTypeDict | tuple[~typing.Any, ~typing.Any] = <class 'numpy.float64'>) Self ¶
Draw a uniform sample from the group. Translations (if applicable) are in the range [-1, 1].
- Parameters:
rng (Generator) – numpy generator object.
batch_axes (Tuple[int, ...]) – Any leading batch axes for the output transforms. Each sampled transform will be different.
dtype (dtype[Any] | None | type[Any] | _SupportsDType[dtype[Any]] | str | tuple[Any, int] | tuple[Any, SupportsIndex | Sequence[SupportsIndex]] | list[Any] | _DTypeDict | tuple[Any, Any])
- Returns:
Sampled group member.
- Return type:
Self
- abstract translation() ndarray[tuple[int, ...], dtype[floating]] [source]¶
Returns a transform’s translation term.
- apply(target: ndarray[tuple[int, ...], dtype[floating]]) ndarray[tuple[int, ...], dtype[floating]] [source]¶
Applies group action to a point.
- class viser.transforms.SOBase[source]¶
Bases:
MatrixLieGroup
Base class for special orthogonal groups.
- classmethod __init_subclass__(matrix_dim: int = 0, parameters_dim: int = 0, tangent_dim: int = 0, space_dim: int = 0) None ¶
Set class properties for subclasses. We default to dummy values.
- __matmul__(other: Self | ndarray[tuple[int, ...], dtype[floating]]) Self | ndarray[tuple[int, ...], dtype[floating]] ¶
Overload for the @ operator.
Switches between the group action (.apply()) and multiplication (.multiply()) based on the type of other.
- abstract adjoint() ndarray[tuple[int, ...], dtype[floating]] ¶
Computes the adjoint, which transforms tangent vectors between tangent spaces.
More precisely, for a transform GroupType:
` GroupType @ exp(omega) = exp(Adj_T @ omega) @ GroupType `
In robotics, typically used for transforming twists, wrenches, and Jacobians across different reference frames.
- abstract apply(target: ndarray[tuple[int, ...], dtype[floating]]) ndarray[tuple[int, ...], dtype[floating]] ¶
Applies group action to a point.
- abstract as_matrix() ndarray[tuple[int, ...], dtype[floating]] ¶
Get transformation as a matrix. Homogeneous for SE groups.
- abstract classmethod exp(tangent: ndarray[tuple[int, ...], dtype[floating]]) Self ¶
Computes expm(wedge(tangent)).
- abstract classmethod from_matrix(matrix: ndarray[tuple[int, ...], dtype[floating]]) Self ¶
Get group member from matrix representation.
- get_batch_axes() Tuple[int, ...] ¶
Return any leading batch axes in contained parameters. If an array of shape (100, 4) is placed in the wxyz field of an SO3 object, for example, this will return (100,).
- abstract classmethod identity(batch_axes: ~typing.Tuple[int, ...] = (), dtype: ~numpy.dtype[~typing.Any] | None | type[~typing.Any] | ~numpy._typing._dtype_like._SupportsDType[~numpy.dtype[~typing.Any]] | str | tuple[~typing.Any, int] | tuple[~typing.Any, ~typing.SupportsIndex | ~collections.abc.Sequence[~typing.SupportsIndex]] | list[~typing.Any] | ~numpy._typing._dtype_like._DTypeDict | tuple[~typing.Any, ~typing.Any] = <class 'numpy.float64'>) Self ¶
Returns identity element.
- Parameters:
- Returns:
Identity element.
- Return type:
Self
- abstract inverse() Self ¶
Computes the inverse of our transform.
- Returns:
Output.
- Return type:
Self
- abstract log() ndarray[tuple[int, ...], dtype[floating]] ¶
Computes vee(logm(transformation matrix)).
- abstract multiply(other: Self) Self ¶
Composes this transformation with another.
- Returns:
self @ other
- Parameters:
other (Self)
- Return type:
Self
- abstract normalize() Self ¶
Normalize/projects values and returns.
- Returns:
Normalized group member.
- Return type:
Self
- abstract classmethod sample_uniform(rng: ~numpy.random._generator.Generator, batch_axes: ~typing.Tuple[int, ...] = (), dtype: ~numpy.dtype[~typing.Any] | None | type[~typing.Any] | ~numpy._typing._dtype_like._SupportsDType[~numpy.dtype[~typing.Any]] | str | tuple[~typing.Any, int] | tuple[~typing.Any, ~typing.SupportsIndex | ~collections.abc.Sequence[~typing.SupportsIndex]] | list[~typing.Any] | ~numpy._typing._dtype_like._DTypeDict | tuple[~typing.Any, ~typing.Any] = <class 'numpy.float64'>) Self ¶
Draw a uniform sample from the group. Translations (if applicable) are in the range [-1, 1].
- Parameters:
rng (Generator) – numpy generator object.
batch_axes (Tuple[int, ...]) – Any leading batch axes for the output transforms. Each sampled transform will be different.
dtype (dtype[Any] | None | type[Any] | _SupportsDType[dtype[Any]] | str | tuple[Any, int] | tuple[Any, SupportsIndex | Sequence[SupportsIndex]] | list[Any] | _DTypeDict | tuple[Any, Any])
- Returns:
Sampled group member.
- Return type:
Self
- class viser.transforms.SE2[source]¶
-
Special Euclidean group for proper rigid transforms in 2D. Broadcasting rules are the same as for numpy.
Ported to numpy from jaxlie.SE2.
Internal parameterization is (cos, sin, x, y). Tangent parameterization is (vx, vy, omega).
- unit_complex_xy: npt.NDArray[np.floating]¶
Internal parameters. (cos, sin, x, y). Shape should be (*, 4).
- static from_xy_theta(x: float | ndarray[tuple[int, ...], dtype[floating]], y: float | ndarray[tuple[int, ...], dtype[floating]], theta: float | ndarray[tuple[int, ...], dtype[floating]]) SE2 [source]¶
Construct a transformation from standard 2D pose parameters.
This is not the same as integrating over a length-3 twist.
- classmethod from_rotation_and_translation(rotation: SO2, translation: ndarray[tuple[int, ...], dtype[floating]]) SE2 [source]¶
Construct a rigid transform from a rotation and a translation.
- translation() ndarray[tuple[int, ...], dtype[floating]] [source]¶
Returns a transform’s translation term.
- classmethod identity(batch_axes: ~typing.Tuple[int, ...] = (), dtype: ~numpy.dtype[~typing.Any] | None | type[~typing.Any] | ~numpy._typing._dtype_like._SupportsDType[~numpy.dtype[~typing.Any]] | str | tuple[~typing.Any, int] | tuple[~typing.Any, ~typing.SupportsIndex | ~collections.abc.Sequence[~typing.SupportsIndex]] | list[~typing.Any] | ~numpy._typing._dtype_like._DTypeDict | tuple[~typing.Any, ~typing.Any] = <class 'numpy.float64'>) SE2 [source]¶
Returns identity element.
- Parameters:
- Returns:
Identity element.
- Return type:
- classmethod from_matrix(matrix: ndarray[tuple[int, ...], dtype[floating]]) SE2 [source]¶
Get group member from matrix representation.
- as_matrix() ndarray[tuple[int, ...], dtype[floating]] [source]¶
Get transformation as a matrix. Homogeneous for SE groups.
- classmethod exp(tangent: ndarray[tuple[int, ...], dtype[floating]]) SE2 [source]¶
Computes expm(wedge(tangent)).
- log() ndarray[tuple[int, ...], dtype[floating]] [source]¶
Computes vee(logm(transformation matrix)).
- adjoint() ndarray[tuple[int, ...], dtype[floating]] [source]¶
Computes the adjoint, which transforms tangent vectors between tangent spaces.
More precisely, for a transform GroupType:
` GroupType @ exp(omega) = exp(Adj_T @ omega) @ GroupType `
In robotics, typically used for transforming twists, wrenches, and Jacobians across different reference frames.
- __matmul__(other: Self | ndarray[tuple[int, ...], dtype[floating]]) Self | ndarray[tuple[int, ...], dtype[floating]] ¶
Overload for the @ operator.
Switches between the group action (.apply()) and multiplication (.multiply()) based on the type of other.
- apply(target: ndarray[tuple[int, ...], dtype[floating]]) ndarray[tuple[int, ...], dtype[floating]] ¶
Applies group action to a point.
- classmethod from_rotation(rotation: ContainedSOType) Self ¶
- Parameters:
rotation (ContainedSOType)
- Return type:
Self
- get_batch_axes() Tuple[int, ...] ¶
Return any leading batch axes in contained parameters. If an array of shape (100, 4) is placed in the wxyz field of an SO3 object, for example, this will return (100,).
- inverse() Self ¶
Computes the inverse of our transform.
- Returns:
Output.
- Return type:
Self
- multiply(other: Self) Self ¶
Composes this transformation with another.
- Returns:
self @ other
- Parameters:
other (Self)
- Return type:
Self
- normalize() Self ¶
Normalize/projects values and returns.
- Returns:
Normalized group member.
- Return type:
Self
- classmethod sample_uniform(rng: ~numpy.random._generator.Generator, batch_axes: ~typing.Tuple[int, ...] = (), dtype: ~numpy.dtype[~typing.Any] | None | type[~typing.Any] | ~numpy._typing._dtype_like._SupportsDType[~numpy.dtype[~typing.Any]] | str | tuple[~typing.Any, int] | tuple[~typing.Any, ~typing.SupportsIndex | ~collections.abc.Sequence[~typing.SupportsIndex]] | list[~typing.Any] | ~numpy._typing._dtype_like._DTypeDict | tuple[~typing.Any, ~typing.Any] = <class 'numpy.float64'>) SE2 [source]¶
Draw a uniform sample from the group. Translations (if applicable) are in the range [-1, 1].
- Parameters:
rng (Generator) – numpy generator object.
batch_axes (Tuple[int, ...]) – Any leading batch axes for the output transforms. Each sampled transform will be different.
dtype (dtype[Any] | None | type[Any] | _SupportsDType[dtype[Any]] | str | tuple[Any, int] | tuple[Any, SupportsIndex | Sequence[SupportsIndex]] | list[Any] | _DTypeDict | tuple[Any, Any])
- Returns:
Sampled group member.
- Return type:
- class viser.transforms.SE3[source]¶
-
Special Euclidean group for proper rigid transforms in 3D. Broadcasting rules are the same as for numpy.
Ported to numpy from jaxlie.SE3.
Internal parameterization is (qw, qx, qy, qz, x, y, z). Tangent parameterization is (vx, vy, vz, omega_x, omega_y, omega_z).
- wxyz_xyz: npt.NDArray[np.floating]¶
Internal parameters. wxyz quaternion followed by xyz translation. Shape should be (*, 7).
- classmethod from_rotation_and_translation(rotation: SO3, translation: ndarray[tuple[int, ...], dtype[floating]]) SE3 [source]¶
Construct a rigid transform from a rotation and a translation.
- translation() ndarray[tuple[int, ...], dtype[floating]] [source]¶
Returns a transform’s translation term.
- classmethod identity(batch_axes: ~typing.Tuple[int, ...] = (), dtype: ~numpy.dtype[~typing.Any] | None | type[~typing.Any] | ~numpy._typing._dtype_like._SupportsDType[~numpy.dtype[~typing.Any]] | str | tuple[~typing.Any, int] | tuple[~typing.Any, ~typing.SupportsIndex | ~collections.abc.Sequence[~typing.SupportsIndex]] | list[~typing.Any] | ~numpy._typing._dtype_like._DTypeDict | tuple[~typing.Any, ~typing.Any] = <class 'numpy.float64'>) SE3 [source]¶
Returns identity element.
- Parameters:
- Returns:
Identity element.
- Return type:
- classmethod from_matrix(matrix: ndarray[tuple[int, ...], dtype[floating]]) SE3 [source]¶
Get group member from matrix representation.
- as_matrix() ndarray[tuple[int, ...], dtype[floating]] [source]¶
Get transformation as a matrix. Homogeneous for SE groups.
- classmethod exp(tangent: ndarray[tuple[int, ...], dtype[floating]]) SE3 [source]¶
Computes expm(wedge(tangent)).
- log() ndarray[tuple[int, ...], dtype[floating]] [source]¶
Computes vee(logm(transformation matrix)).
- adjoint() ndarray[tuple[int, ...], dtype[floating]] [source]¶
Computes the adjoint, which transforms tangent vectors between tangent spaces.
More precisely, for a transform GroupType:
` GroupType @ exp(omega) = exp(Adj_T @ omega) @ GroupType `
In robotics, typically used for transforming twists, wrenches, and Jacobians across different reference frames.
- __matmul__(other: Self | ndarray[tuple[int, ...], dtype[floating]]) Self | ndarray[tuple[int, ...], dtype[floating]] ¶
Overload for the @ operator.
Switches between the group action (.apply()) and multiplication (.multiply()) based on the type of other.
- apply(target: ndarray[tuple[int, ...], dtype[floating]]) ndarray[tuple[int, ...], dtype[floating]] ¶
Applies group action to a point.
- classmethod from_rotation(rotation: ContainedSOType) Self ¶
- Parameters:
rotation (ContainedSOType)
- Return type:
Self
- get_batch_axes() Tuple[int, ...] ¶
Return any leading batch axes in contained parameters. If an array of shape (100, 4) is placed in the wxyz field of an SO3 object, for example, this will return (100,).
- inverse() Self ¶
Computes the inverse of our transform.
- Returns:
Output.
- Return type:
Self
- multiply(other: Self) Self ¶
Composes this transformation with another.
- Returns:
self @ other
- Parameters:
other (Self)
- Return type:
Self
- normalize() Self ¶
Normalize/projects values and returns.
- Returns:
Normalized group member.
- Return type:
Self
- classmethod sample_uniform(rng: ~numpy.random._generator.Generator, batch_axes: ~typing.Tuple[int, ...] = (), dtype: ~numpy.dtype[~typing.Any] | None | type[~typing.Any] | ~numpy._typing._dtype_like._SupportsDType[~numpy.dtype[~typing.Any]] | str | tuple[~typing.Any, int] | tuple[~typing.Any, ~typing.SupportsIndex | ~collections.abc.Sequence[~typing.SupportsIndex]] | list[~typing.Any] | ~numpy._typing._dtype_like._DTypeDict | tuple[~typing.Any, ~typing.Any] = <class 'numpy.float64'>) SE3 [source]¶
Draw a uniform sample from the group. Translations (if applicable) are in the range [-1, 1].
- Parameters:
rng (Generator) – numpy generator object.
batch_axes (Tuple[int, ...]) – Any leading batch axes for the output transforms. Each sampled transform will be different.
dtype (dtype[Any] | None | type[Any] | _SupportsDType[dtype[Any]] | str | tuple[Any, int] | tuple[Any, SupportsIndex | Sequence[SupportsIndex]] | list[Any] | _DTypeDict | tuple[Any, Any])
- Returns:
Sampled group member.
- Return type:
- class viser.transforms.SO2[source]¶
Bases:
SOBase
Special orthogonal group for 2D rotations. Broadcasting rules are the same as for numpy.
Ported to numpy from jaxlie.SO2.
Internal parameterization is (cos, sin). Tangent parameterization is (omega,).
- unit_complex: npt.NDArray[np.floating]¶
Internal parameters. (cos, sin). Shape should be (*, 2).
- static from_radians(theta: float | ndarray[tuple[int, ...], dtype[floating]]) SO2 [source]¶
Construct a rotation object from a scalar angle.
- as_radians() ndarray[tuple[int, ...], dtype[floating]] [source]¶
Compute a scalar angle from a rotation object.
- classmethod identity(batch_axes: ~typing.Tuple[int, ...] = (), dtype: ~numpy.dtype[~typing.Any] | None | type[~typing.Any] | ~numpy._typing._dtype_like._SupportsDType[~numpy.dtype[~typing.Any]] | str | tuple[~typing.Any, int] | tuple[~typing.Any, ~typing.SupportsIndex | ~collections.abc.Sequence[~typing.SupportsIndex]] | list[~typing.Any] | ~numpy._typing._dtype_like._DTypeDict | tuple[~typing.Any, ~typing.Any] = <class 'numpy.float64'>) SO2 [source]¶
Returns identity element.
- Parameters:
- Returns:
Identity element.
- Return type:
- classmethod from_matrix(matrix: ndarray[tuple[int, ...], dtype[floating]]) SO2 [source]¶
Get group member from matrix representation.
- as_matrix() ndarray[tuple[int, ...], dtype[floating]] [source]¶
Get transformation as a matrix. Homogeneous for SE groups.
- apply(target: ndarray[tuple[int, ...], dtype[floating]]) ndarray[tuple[int, ...], dtype[floating]] [source]¶
Applies group action to a point.
- classmethod exp(tangent: ndarray[tuple[int, ...], dtype[floating]]) SO2 [source]¶
Computes expm(wedge(tangent)).
- log() ndarray[tuple[int, ...], dtype[floating]] [source]¶
Computes vee(logm(transformation matrix)).
- adjoint() ndarray[tuple[int, ...], dtype[floating]] [source]¶
Computes the adjoint, which transforms tangent vectors between tangent spaces.
More precisely, for a transform GroupType:
` GroupType @ exp(omega) = exp(Adj_T @ omega) @ GroupType `
In robotics, typically used for transforming twists, wrenches, and Jacobians across different reference frames.
- normalize() SO2 [source]¶
Normalize/projects values and returns.
- Returns:
Normalized group member.
- Return type:
- classmethod __init_subclass__(matrix_dim: int = 0, parameters_dim: int = 0, tangent_dim: int = 0, space_dim: int = 0) None ¶
Set class properties for subclasses. We default to dummy values.
- __matmul__(other: Self | ndarray[tuple[int, ...], dtype[floating]]) Self | ndarray[tuple[int, ...], dtype[floating]] ¶
Overload for the @ operator.
Switches between the group action (.apply()) and multiplication (.multiply()) based on the type of other.
- get_batch_axes() Tuple[int, ...] ¶
Return any leading batch axes in contained parameters. If an array of shape (100, 4) is placed in the wxyz field of an SO3 object, for example, this will return (100,).
- classmethod sample_uniform(rng: ~numpy.random._generator.Generator, batch_axes: ~typing.Tuple[int, ...] = (), dtype: ~numpy.dtype[~typing.Any] | None | type[~typing.Any] | ~numpy._typing._dtype_like._SupportsDType[~numpy.dtype[~typing.Any]] | str | tuple[~typing.Any, int] | tuple[~typing.Any, ~typing.SupportsIndex | ~collections.abc.Sequence[~typing.SupportsIndex]] | list[~typing.Any] | ~numpy._typing._dtype_like._DTypeDict | tuple[~typing.Any, ~typing.Any] = <class 'numpy.float64'>) SO2 [source]¶
Draw a uniform sample from the group. Translations (if applicable) are in the range [-1, 1].
- Parameters:
rng (Generator) – numpy generator object.
batch_axes (Tuple[int, ...]) – Any leading batch axes for the output transforms. Each sampled transform will be different.
dtype (dtype[Any] | None | type[Any] | _SupportsDType[dtype[Any]] | str | tuple[Any, int] | tuple[Any, SupportsIndex | Sequence[SupportsIndex]] | list[Any] | _DTypeDict | tuple[Any, Any])
- Returns:
Sampled group member.
- Return type:
- class viser.transforms.SO3[source]¶
Bases:
SOBase
Special orthogonal group for 3D rotations. Broadcasting rules are the same as for numpy.
Ported to numpy from jaxlie.SO3.
Internal parameterization is (qw, qx, qy, qz). Tangent parameterization is (omega_x, omega_y, omega_z).
- wxyz: onpt.NDArray[onp.floating]¶
Internal parameters. (w, x, y, z) quaternion. Shape should be (*, 4).
- static from_x_radians(theta: float | ndarray[tuple[int, ...], dtype[floating]]) SO3 [source]¶
Generates a x-axis rotation.
- static from_y_radians(theta: float | ndarray[tuple[int, ...], dtype[floating]]) SO3 [source]¶
Generates a y-axis rotation.
- static from_z_radians(theta: float | ndarray[tuple[int, ...], dtype[floating]]) SO3 [source]¶
Generates a z-axis rotation.
- static from_rpy_radians(roll: float | ndarray[tuple[int, ...], dtype[floating]], pitch: float | ndarray[tuple[int, ...], dtype[floating]], yaw: float | ndarray[tuple[int, ...], dtype[floating]]) SO3 [source]¶
Generates a transform from a set of Euler angles. Uses the ZYX mobile robot convention.
- Parameters:
- Returns:
Output.
- Return type:
- static from_quaternion_xyzw(xyzw: ndarray[tuple[int, ...], dtype[floating]]) SO3 [source]¶
Construct a rotation from an xyzw quaternion.
Note that wxyz quaternions can be constructed using the default dataclass constructor.
- as_quaternion_xyzw() ndarray[tuple[int, ...], dtype[floating]] [source]¶
Grab parameters as xyzw quaternion.
- as_rpy_radians() RollPitchYaw [source]¶
Computes roll, pitch, and yaw angles. Uses the ZYX mobile robot convention.
- Returns:
NamedTuple containing Euler angles in radians.
- Return type:
RollPitchYaw
- compute_roll_radians() ndarray[tuple[int, ...], dtype[floating]] [source]¶
Compute roll angle. Uses the ZYX mobile robot convention.
- compute_pitch_radians() ndarray[tuple[int, ...], dtype[floating]] [source]¶
Compute pitch angle. Uses the ZYX mobile robot convention.
- compute_yaw_radians() ndarray[tuple[int, ...], dtype[floating]] [source]¶
Compute yaw angle. Uses the ZYX mobile robot convention.
- classmethod identity(batch_axes: ~typing.Tuple[int, ...] = (), dtype: ~numpy.dtype[~typing.Any] | None | type[~typing.Any] | ~numpy._typing._dtype_like._SupportsDType[~numpy.dtype[~typing.Any]] | str | tuple[~typing.Any, int] | tuple[~typing.Any, ~typing.SupportsIndex | ~collections.abc.Sequence[~typing.SupportsIndex]] | list[~typing.Any] | ~numpy._typing._dtype_like._DTypeDict | tuple[~typing.Any, ~typing.Any] = <class 'numpy.float64'>) SO3 [source]¶
Returns identity element.
- Parameters:
- Returns:
Identity element.
- Return type:
- classmethod from_matrix(matrix: ndarray[tuple[int, ...], dtype[floating]]) SO3 [source]¶
Get group member from matrix representation.
- as_matrix() ndarray[tuple[int, ...], dtype[floating]] [source]¶
Get transformation as a matrix. Homogeneous for SE groups.
- apply(target: ndarray[tuple[int, ...], dtype[floating]]) ndarray[tuple[int, ...], dtype[floating]] [source]¶
Applies group action to a point.
- classmethod exp(tangent: ndarray[tuple[int, ...], dtype[floating]]) SO3 [source]¶
Computes expm(wedge(tangent)).
- log() ndarray[tuple[int, ...], dtype[floating]] [source]¶
Computes vee(logm(transformation matrix)).
- adjoint() ndarray[tuple[int, ...], dtype[floating]] [source]¶
Computes the adjoint, which transforms tangent vectors between tangent spaces.
More precisely, for a transform GroupType:
` GroupType @ exp(omega) = exp(Adj_T @ omega) @ GroupType `
In robotics, typically used for transforming twists, wrenches, and Jacobians across different reference frames.
- normalize() SO3 [source]¶
Normalize/projects values and returns.
- Returns:
Normalized group member.
- Return type:
- classmethod __init_subclass__(matrix_dim: int = 0, parameters_dim: int = 0, tangent_dim: int = 0, space_dim: int = 0) None ¶
Set class properties for subclasses. We default to dummy values.
- __matmul__(other: Self | ndarray[tuple[int, ...], dtype[floating]]) Self | ndarray[tuple[int, ...], dtype[floating]] ¶
Overload for the @ operator.
Switches between the group action (.apply()) and multiplication (.multiply()) based on the type of other.
- get_batch_axes() Tuple[int, ...] ¶
Return any leading batch axes in contained parameters. If an array of shape (100, 4) is placed in the wxyz field of an SO3 object, for example, this will return (100,).
- classmethod sample_uniform(rng: ~numpy.random._generator.Generator, batch_axes: ~typing.Tuple[int, ...] = (), dtype: ~numpy.dtype[~typing.Any] | None | type[~typing.Any] | ~numpy._typing._dtype_like._SupportsDType[~numpy.dtype[~typing.Any]] | str | tuple[~typing.Any, int] | tuple[~typing.Any, ~typing.SupportsIndex | ~collections.abc.Sequence[~typing.SupportsIndex]] | list[~typing.Any] | ~numpy._typing._dtype_like._DTypeDict | tuple[~typing.Any, ~typing.Any] = <class 'numpy.float64'>) SO3 [source]¶
Draw a uniform sample from the group. Translations (if applicable) are in the range [-1, 1].
- Parameters:
rng (Generator) – numpy generator object.
batch_axes (Tuple[int, ...]) – Any leading batch axes for the output transforms. Each sampled transform will be different.
dtype (dtype[Any] | None | type[Any] | _SupportsDType[dtype[Any]] | str | tuple[Any, int] | tuple[Any, SupportsIndex | Sequence[SupportsIndex]] | list[Any] | _DTypeDict | tuple[Any, Any])
- Returns:
Sampled group member.
- Return type: