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.

matrix_dim: ClassVar[int]#

Dimension of square matrix output from .as_matrix().

parameters_dim: ClassVar[int]#

Dimension of underlying parameters, .parameters().

tangent_dim: ClassVar[int]#

Dimension of tangent space.

space_dim: ClassVar[int]#

Dimension of coordinates that can be transformed.

__matmul__(other: Self) Self[source]#
__matmul__(other: ndarray[Any, dtype[floating]]) ndarray[Any, 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: Tuple[int, ] = ()) Self[source]#

Returns identity element.

Parameters:

batch_axes (Tuple[int, ]) – Any leading batch axes for the output transform.

Returns:

Identity element.

Return type:

Self

abstract classmethod from_matrix(matrix: ndarray[Any, dtype[floating]]) Self[source]#

Get group member from matrix representation.

Parameters:

matrix (ndarray[Any, dtype[floating]]) – Matrix representaiton.

Returns:

Group member.

Return type:

Self

abstract as_matrix() ndarray[Any, dtype[floating]][source]#

Get transformation as a matrix. Homogeneous for SE groups.

Return type:

ndarray[Any, dtype[floating]]

abstract parameters() ndarray[Any, dtype[floating]][source]#

Get underlying representation.

Return type:

ndarray[Any, dtype[floating]]

abstract apply(target: ndarray[Any, dtype[floating]]) ndarray[Any, dtype[floating]][source]#

Applies group action to a point.

Parameters:

target (ndarray[Any, dtype[floating]]) – Point to transform.

Returns:

Transformed point.

Return type:

ndarray[Any, dtype[floating]]

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[Any, dtype[floating]]) Self[source]#

Computes expm(wedge(tangent)).

Parameters:

tangent (ndarray[Any, dtype[floating]]) – Tangent vector to take the exponential of.

Returns:

Output.

Return type:

Self

abstract log() ndarray[Any, dtype[floating]][source]#

Computes vee(logm(transformation matrix)).

Returns:

Output. Shape should be (tangent_dim,).

Return type:

ndarray[Any, dtype[floating]]

abstract adjoint() ndarray[Any, 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.

Returns:

Output. Shape should be (tangent_dim, tangent_dim).

Return type:

ndarray[Any, dtype[floating]]

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

get_batch_axes() Tuple[int, ...][source]#

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,).

Return type:

Tuple[int, …]

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[Any, dtype[floating]]) Self[source]#

Construct a rigid transform from a rotation and a translation.

Parameters:
  • rotation (ContainedSOType) – Rotation term.

  • translation (ndarray[Any, dtype[floating]]) – translation term.

Returns:

Constructed transformation.

Return type:

Self

classmethod from_rotation(rotation: ContainedSOType) Self[source]#
Parameters:

rotation (ContainedSOType) –

Return type:

Self

classmethod from_translation(translation: ndarray[Any, dtype[floating]]) Self[source]#
Parameters:

translation (ndarray[Any, dtype[floating]]) –

Return type:

Self

__matmul__(other: Self | ndarray[Any, dtype[floating]]) Self | ndarray[Any, dtype[floating]]#

Overload for the @ operator.

Switches between the group action (.apply()) and multiplication (.multiply()) based on the type of other.

Parameters:

other (Self | ndarray[Any, dtype[floating]]) –

Return type:

Self | ndarray[Any, dtype[floating]]

abstract adjoint() ndarray[Any, 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.

Returns:

Output. Shape should be (tangent_dim, tangent_dim).

Return type:

ndarray[Any, dtype[floating]]

abstract as_matrix() ndarray[Any, dtype[floating]]#

Get transformation as a matrix. Homogeneous for SE groups.

Return type:

ndarray[Any, dtype[floating]]

abstract classmethod exp(tangent: ndarray[Any, dtype[floating]]) Self#

Computes expm(wedge(tangent)).

Parameters:

tangent (ndarray[Any, dtype[floating]]) – Tangent vector to take the exponential of.

Returns:

Output.

Return type:

Self

abstract classmethod from_matrix(matrix: ndarray[Any, dtype[floating]]) Self#

Get group member from matrix representation.

Parameters:

matrix (ndarray[Any, dtype[floating]]) – Matrix representaiton.

Returns:

Group member.

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,).

Return type:

Tuple[int, …]

abstract classmethod identity(batch_axes: Tuple[int, ] = ()) Self#

Returns identity element.

Parameters:

batch_axes (Tuple[int, ]) – Any leading batch axes for the output transform.

Returns:

Identity element.

Return type:

Self

abstract log() ndarray[Any, dtype[floating]]#

Computes vee(logm(transformation matrix)).

Returns:

Output. Shape should be (tangent_dim,).

Return type:

ndarray[Any, dtype[floating]]

abstract parameters() ndarray[Any, dtype[floating]]#

Get underlying representation.

Return type:

ndarray[Any, dtype[floating]]

abstract rotation() ContainedSOType[source]#

Returns a transform’s rotation term.

Return type:

ContainedSOType

matrix_dim: ClassVar[int]#

Dimension of square matrix output from .as_matrix().

parameters_dim: ClassVar[int]#

Dimension of underlying parameters, .parameters().

tangent_dim: ClassVar[int]#

Dimension of tangent space.

space_dim: ClassVar[int]#

Dimension of coordinates that can be transformed.

abstract translation() ndarray[Any, dtype[floating]][source]#

Returns a transform’s translation term.

Return type:

ndarray[Any, dtype[floating]]

apply(target: ndarray[Any, dtype[floating]]) ndarray[Any, dtype[floating]][source]#

Applies group action to a point.

Parameters:

target (ndarray[Any, dtype[floating]]) – Point to transform.

Returns:

Transformed point.

Return type:

ndarray[Any, dtype[floating]]

multiply(other: Self) Self[source]#

Composes this transformation with another.

Returns:

self @ other

Parameters:

other (Self) –

Return type:

Self

inverse() Self[source]#

Computes the inverse of our transform.

Returns:

Output.

Return type:

Self

normalize() Self[source]#

Normalize/projects values and returns.

Returns:

Normalized group member.

Return type:

Self

class viser.transforms.SOBase[source]#

Bases: MatrixLieGroup

Base class for special orthogonal groups.

__matmul__(other: Self | ndarray[Any, dtype[floating]]) Self | ndarray[Any, dtype[floating]]#

Overload for the @ operator.

Switches between the group action (.apply()) and multiplication (.multiply()) based on the type of other.

Parameters:

other (Self | ndarray[Any, dtype[floating]]) –

Return type:

Self | ndarray[Any, dtype[floating]]

abstract adjoint() ndarray[Any, 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.

Returns:

Output. Shape should be (tangent_dim, tangent_dim).

Return type:

ndarray[Any, dtype[floating]]

abstract apply(target: ndarray[Any, dtype[floating]]) ndarray[Any, dtype[floating]]#

Applies group action to a point.

Parameters:

target (ndarray[Any, dtype[floating]]) – Point to transform.

Returns:

Transformed point.

Return type:

ndarray[Any, dtype[floating]]

abstract as_matrix() ndarray[Any, dtype[floating]]#

Get transformation as a matrix. Homogeneous for SE groups.

Return type:

ndarray[Any, dtype[floating]]

abstract classmethod exp(tangent: ndarray[Any, dtype[floating]]) Self#

Computes expm(wedge(tangent)).

Parameters:

tangent (ndarray[Any, dtype[floating]]) – Tangent vector to take the exponential of.

Returns:

Output.

Return type:

Self

abstract classmethod from_matrix(matrix: ndarray[Any, dtype[floating]]) Self#

Get group member from matrix representation.

Parameters:

matrix (ndarray[Any, dtype[floating]]) – Matrix representaiton.

Returns:

Group member.

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,).

Return type:

Tuple[int, …]

abstract classmethod identity(batch_axes: Tuple[int, ] = ()) Self#

Returns identity element.

Parameters:

batch_axes (Tuple[int, ]) – Any leading batch axes for the output transform.

Returns:

Identity element.

Return type:

Self

abstract inverse() Self#

Computes the inverse of our transform.

Returns:

Output.

Return type:

Self

abstract log() ndarray[Any, dtype[floating]]#

Computes vee(logm(transformation matrix)).

Returns:

Output. Shape should be (tangent_dim,).

Return type:

ndarray[Any, dtype[floating]]

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 parameters() ndarray[Any, dtype[floating]]#

Get underlying representation.

Return type:

ndarray[Any, dtype[floating]]

matrix_dim: ClassVar[int]#

Dimension of square matrix output from .as_matrix().

parameters_dim: ClassVar[int]#

Dimension of underlying parameters, .parameters().

tangent_dim: ClassVar[int]#

Dimension of tangent space.

space_dim: ClassVar[int]#

Dimension of coordinates that can be transformed.

class viser.transforms.SE2[source]#

Bases: SEBase[SO2]

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: ndarray[Any, dtype[floating]]#

Internal parameters. (cos, sin, x, y). Shape should be (*, 4).

static from_xy_theta(x: float | ndarray[Any, dtype[floating]], y: float | ndarray[Any, dtype[floating]], theta: float | ndarray[Any, dtype[floating]]) SE2[source]#

Construct a transformation from standard 2D pose parameters.

This is not the same as integrating over a length-3 twist.

Parameters:
  • x (float | ndarray[Any, dtype[floating]]) –

  • y (float | ndarray[Any, dtype[floating]]) –

  • theta (float | ndarray[Any, dtype[floating]]) –

Return type:

SE2

classmethod from_rotation_and_translation(rotation: SO2, translation: ndarray[Any, dtype[floating]]) SE2[source]#

Construct a rigid transform from a rotation and a translation.

Parameters:
  • rotation (SO2) – Rotation term.

  • translation (ndarray[Any, dtype[floating]]) – translation term.

Returns:

Constructed transformation.

Return type:

SE2

rotation() SO2[source]#

Returns a transform’s rotation term.

Return type:

SO2

translation() ndarray[Any, dtype[floating]][source]#

Returns a transform’s translation term.

Return type:

ndarray[Any, dtype[floating]]

classmethod identity(batch_axes: Tuple[int, ] = ()) SE2[source]#

Returns identity element.

Parameters:

batch_axes (Tuple[int, ]) – Any leading batch axes for the output transform.

Returns:

Identity element.

Return type:

SE2

classmethod from_matrix(matrix: ndarray[Any, dtype[floating]]) SE2[source]#

Get group member from matrix representation.

Parameters:

matrix (ndarray[Any, dtype[floating]]) – Matrix representaiton.

Returns:

Group member.

Return type:

SE2

parameters() ndarray[Any, dtype[floating]][source]#

Get underlying representation.

Return type:

ndarray[Any, dtype[floating]]

as_matrix() ndarray[Any, dtype[floating]][source]#

Get transformation as a matrix. Homogeneous for SE groups.

Return type:

ndarray[Any, dtype[floating]]

classmethod exp(tangent: ndarray[Any, dtype[floating]]) SE2[source]#

Computes expm(wedge(tangent)).

Parameters:

tangent (ndarray[Any, dtype[floating]]) – Tangent vector to take the exponential of.

Returns:

Output.

Return type:

SE2

log() ndarray[Any, dtype[floating]][source]#

Computes vee(logm(transformation matrix)).

Returns:

Output. Shape should be (tangent_dim,).

Return type:

ndarray[Any, dtype[floating]]

__matmul__(other: Self | ndarray[Any, dtype[floating]]) Self | ndarray[Any, dtype[floating]]#

Overload for the @ operator.

Switches between the group action (.apply()) and multiplication (.multiply()) based on the type of other.

Parameters:

other (Self | ndarray[Any, dtype[floating]]) –

Return type:

Self | ndarray[Any, dtype[floating]]

adjoint() ndarray[Any, 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.

Returns:

Output. Shape should be (tangent_dim, tangent_dim).

Parameters:

self (SE2) –

Return type:

ndarray[Any, dtype[floating]]

apply(target: ndarray[Any, dtype[floating]]) ndarray[Any, dtype[floating]]#

Applies group action to a point.

Parameters:

target (ndarray[Any, dtype[floating]]) – Point to transform.

Returns:

Transformed point.

Return type:

ndarray[Any, dtype[floating]]

classmethod from_rotation(rotation: ContainedSOType) Self#
Parameters:

rotation (ContainedSOType) –

Return type:

Self

classmethod from_translation(translation: ndarray[Any, dtype[floating]]) Self#
Parameters:

translation (ndarray[Any, dtype[floating]]) –

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,).

Return type:

Tuple[int, …]

inverse() Self#

Computes the inverse of our transform.

Returns:

Output.

Return type:

Self

matrix_dim: ClassVar[int] = 3#

Dimension of square matrix output from .as_matrix().

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

parameters_dim: ClassVar[int] = 4#

Dimension of underlying parameters, .parameters().

space_dim: ClassVar[int] = 2#

Dimension of coordinates that can be transformed.

tangent_dim: ClassVar[int] = 3#

Dimension of tangent space.

class viser.transforms.SE3[source]#

Bases: SEBase[SO3]

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: onpt.NDArray[onp.floating]#

Internal parameters. wxyz quaternion followed by xyz translation. Shape should be (*, 7).

classmethod from_rotation_and_translation(rotation: SO3, translation: ndarray[Any, dtype[floating]]) SE3[source]#

Construct a rigid transform from a rotation and a translation.

Parameters:
  • rotation (SO3) – Rotation term.

  • translation (ndarray[Any, dtype[floating]]) – translation term.

Returns:

Constructed transformation.

Return type:

SE3

rotation() SO3[source]#

Returns a transform’s rotation term.

Return type:

SO3

translation() ndarray[Any, dtype[floating]][source]#

Returns a transform’s translation term.

Return type:

ndarray[Any, dtype[floating]]

classmethod identity(batch_axes: Tuple[int, ] = ()) SE3[source]#

Returns identity element.

Parameters:

batch_axes (Tuple[int, ]) – Any leading batch axes for the output transform.

Returns:

Identity element.

Return type:

SE3

classmethod from_matrix(matrix: ndarray[Any, dtype[floating]]) SE3[source]#

Get group member from matrix representation.

Parameters:

matrix (ndarray[Any, dtype[floating]]) – Matrix representaiton.

Returns:

Group member.

Return type:

SE3

as_matrix() ndarray[Any, dtype[floating]][source]#

Get transformation as a matrix. Homogeneous for SE groups.

Return type:

ndarray[Any, dtype[floating]]

parameters() ndarray[Any, dtype[floating]][source]#

Get underlying representation.

Return type:

ndarray[Any, dtype[floating]]

classmethod exp(tangent: ndarray[Any, dtype[floating]]) SE3[source]#

Computes expm(wedge(tangent)).

Parameters:

tangent (ndarray[Any, dtype[floating]]) – Tangent vector to take the exponential of.

Returns:

Output.

Return type:

SE3

log() ndarray[Any, dtype[floating]][source]#

Computes vee(logm(transformation matrix)).

Returns:

Output. Shape should be (tangent_dim,).

Return type:

ndarray[Any, dtype[floating]]

__matmul__(other: Self | ndarray[Any, dtype[floating]]) Self | ndarray[Any, dtype[floating]]#

Overload for the @ operator.

Switches between the group action (.apply()) and multiplication (.multiply()) based on the type of other.

Parameters:

other (Self | ndarray[Any, dtype[floating]]) –

Return type:

Self | ndarray[Any, dtype[floating]]

adjoint() ndarray[Any, 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.

Returns:

Output. Shape should be (tangent_dim, tangent_dim).

Return type:

ndarray[Any, dtype[floating]]

apply(target: ndarray[Any, dtype[floating]]) ndarray[Any, dtype[floating]]#

Applies group action to a point.

Parameters:

target (ndarray[Any, dtype[floating]]) – Point to transform.

Returns:

Transformed point.

Return type:

ndarray[Any, dtype[floating]]

classmethod from_rotation(rotation: ContainedSOType) Self#
Parameters:

rotation (ContainedSOType) –

Return type:

Self

classmethod from_translation(translation: ndarray[Any, dtype[floating]]) Self#
Parameters:

translation (ndarray[Any, dtype[floating]]) –

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,).

Return type:

Tuple[int, …]

inverse() Self#

Computes the inverse of our transform.

Returns:

Output.

Return type:

Self

matrix_dim: ClassVar[int] = 4#

Dimension of square matrix output from .as_matrix().

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

parameters_dim: ClassVar[int] = 7#

Dimension of underlying parameters, .parameters().

space_dim: ClassVar[int] = 3#

Dimension of coordinates that can be transformed.

tangent_dim: ClassVar[int] = 6#

Dimension of tangent space.

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: onpt.NDArray[onp.floating]#

Internal parameters. (cos, sin). Shape should be (*, 2).

static from_radians(theta: float | ndarray[Any, dtype[floating]]) SO2[source]#

Construct a rotation object from a scalar angle.

Parameters:

theta (float | ndarray[Any, dtype[floating]]) –

Return type:

SO2

as_radians() ndarray[Any, dtype[floating]][source]#

Compute a scalar angle from a rotation object.

Return type:

ndarray[Any, dtype[floating]]

classmethod identity(batch_axes: Tuple[int, ] = ()) SO2[source]#

Returns identity element.

Parameters:

batch_axes (Tuple[int, ]) – Any leading batch axes for the output transform.

Returns:

Identity element.

Return type:

SO2

classmethod from_matrix(matrix: ndarray[Any, dtype[floating]]) SO2[source]#

Get group member from matrix representation.

Parameters:

matrix (ndarray[Any, dtype[floating]]) – Matrix representaiton.

Returns:

Group member.

Return type:

SO2

as_matrix() ndarray[Any, dtype[floating]][source]#

Get transformation as a matrix. Homogeneous for SE groups.

Return type:

ndarray[Any, dtype[floating]]

parameters() ndarray[Any, dtype[floating]][source]#

Get underlying representation.

Return type:

ndarray[Any, dtype[floating]]

apply(target: ndarray[Any, dtype[floating]]) ndarray[Any, dtype[floating]][source]#

Applies group action to a point.

Parameters:

target (ndarray[Any, dtype[floating]]) – Point to transform.

Returns:

Transformed point.

Return type:

ndarray[Any, dtype[floating]]

multiply(other: SO2) SO2[source]#

Composes this transformation with another.

Returns:

self @ other

Parameters:

other (SO2) –

Return type:

SO2

classmethod exp(tangent: ndarray[Any, dtype[floating]]) SO2[source]#

Computes expm(wedge(tangent)).

Parameters:

tangent (ndarray[Any, dtype[floating]]) – Tangent vector to take the exponential of.

Returns:

Output.

Return type:

SO2

log() ndarray[Any, dtype[floating]][source]#

Computes vee(logm(transformation matrix)).

Returns:

Output. Shape should be (tangent_dim,).

Return type:

ndarray[Any, dtype[floating]]

adjoint() ndarray[Any, 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.

Returns:

Output. Shape should be (tangent_dim, tangent_dim).

Return type:

ndarray[Any, dtype[floating]]

inverse() SO2[source]#

Computes the inverse of our transform.

Returns:

Output.

Return type:

SO2

__matmul__(other: Self | ndarray[Any, dtype[floating]]) Self | ndarray[Any, dtype[floating]]#

Overload for the @ operator.

Switches between the group action (.apply()) and multiplication (.multiply()) based on the type of other.

Parameters:

other (Self | ndarray[Any, dtype[floating]]) –

Return type:

Self | ndarray[Any, dtype[floating]]

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,).

Return type:

Tuple[int, …]

matrix_dim: ClassVar[int] = 2#

Dimension of square matrix output from .as_matrix().

normalize() SO2[source]#

Normalize/projects values and returns.

Returns:

Normalized group member.

Return type:

SO2

parameters_dim: ClassVar[int] = 2#

Dimension of underlying parameters, .parameters().

space_dim: ClassVar[int] = 2#

Dimension of coordinates that can be transformed.

tangent_dim: ClassVar[int] = 1#

Dimension of tangent space.

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[Any, dtype[floating]]) SO3[source]#

Generates a x-axis rotation.

Parameters:
  • angle – X rotation, in radians.

  • theta (float | ndarray[Any, dtype[floating]]) –

Returns:

Output.

Return type:

SO3

static from_y_radians(theta: float | ndarray[Any, dtype[floating]]) SO3[source]#

Generates a y-axis rotation.

Parameters:
  • angle – Y rotation, in radians.

  • theta (float | ndarray[Any, dtype[floating]]) –

Returns:

Output.

Return type:

SO3

static from_z_radians(theta: float | ndarray[Any, dtype[floating]]) SO3[source]#

Generates a z-axis rotation.

Parameters:
  • angle – Z rotation, in radians.

  • theta (float | ndarray[Any, dtype[floating]]) –

Returns:

Output.

Return type:

SO3

static from_rpy_radians(roll: float | ndarray[Any, dtype[floating]], pitch: float | ndarray[Any, dtype[floating]], yaw: float | ndarray[Any, dtype[floating]]) SO3[source]#

Generates a transform from a set of Euler angles. Uses the ZYX mobile robot convention.

Parameters:
  • roll (float | ndarray[Any, dtype[floating]]) – X rotation, in radians. Applied first.

  • pitch (float | ndarray[Any, dtype[floating]]) – Y rotation, in radians. Applied second.

  • yaw (float | ndarray[Any, dtype[floating]]) – Z rotation, in radians. Applied last.

Returns:

Output.

Return type:

SO3

static from_quaternion_xyzw(xyzw: ndarray[Any, dtype[floating]]) SO3[source]#

Construct a rotation from an xyzw quaternion.

Note that wxyz quaternions can be constructed using the default dataclass constructor.

Parameters:

xyzw (ndarray[Any, dtype[floating]]) – xyzw quaternion. Shape should be (*, 4).

Returns:

Output.

Return type:

SO3

as_quaternion_xyzw() ndarray[Any, dtype[floating]][source]#

Grab parameters as xyzw quaternion.

Return type:

ndarray[Any, dtype[floating]]

as_rpy_radians() RollPitchYaw[source]#

Computes roll, pitch, and yaw angles. Uses the ZYX mobile robot convention.

Returns:

Named tuple containing Euler angles in radians.

Return type:

RollPitchYaw

compute_roll_radians() ndarray[Any, dtype[floating]][source]#

Compute roll angle. Uses the ZYX mobile robot convention.

Returns:

Euler angle in radians.

Return type:

ndarray[Any, dtype[floating]]

compute_pitch_radians() ndarray[Any, dtype[floating]][source]#

Compute pitch angle. Uses the ZYX mobile robot convention.

Returns:

Euler angle in radians.

Return type:

ndarray[Any, dtype[floating]]

compute_yaw_radians() ndarray[Any, dtype[floating]][source]#

Compute yaw angle. Uses the ZYX mobile robot convention.

Returns:

Euler angle in radians.

Return type:

ndarray[Any, dtype[floating]]

classmethod identity(batch_axes: Tuple[int, ] = ()) SO3[source]#

Returns identity element.

Parameters:

batch_axes (Tuple[int, ]) – Any leading batch axes for the output transform.

Returns:

Identity element.

Return type:

SO3

classmethod from_matrix(matrix: ndarray[Any, dtype[floating]]) SO3[source]#

Get group member from matrix representation.

Parameters:

matrix (ndarray[Any, dtype[floating]]) – Matrix representaiton.

Returns:

Group member.

Return type:

SO3

as_matrix() ndarray[Any, dtype[floating]][source]#

Get transformation as a matrix. Homogeneous for SE groups.

Return type:

ndarray[Any, dtype[floating]]

parameters() ndarray[Any, dtype[floating]][source]#

Get underlying representation.

Return type:

ndarray[Any, dtype[floating]]

apply(target: ndarray[Any, dtype[floating]]) ndarray[Any, dtype[floating]][source]#

Applies group action to a point.

Parameters:

target (ndarray[Any, dtype[floating]]) – Point to transform.

Returns:

Transformed point.

Return type:

ndarray[Any, dtype[floating]]

multiply(other: SO3) SO3[source]#

Composes this transformation with another.

Returns:

self @ other

Parameters:

other (SO3) –

Return type:

SO3

classmethod exp(tangent: ndarray[Any, dtype[floating]]) SO3[source]#

Computes expm(wedge(tangent)).

Parameters:

tangent (ndarray[Any, dtype[floating]]) – Tangent vector to take the exponential of.

Returns:

Output.

Return type:

SO3

log() ndarray[Any, dtype[floating]][source]#

Computes vee(logm(transformation matrix)).

Returns:

Output. Shape should be (tangent_dim,).

Return type:

ndarray[Any, dtype[floating]]

adjoint() ndarray[Any, 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.

Returns:

Output. Shape should be (tangent_dim, tangent_dim).

Return type:

ndarray[Any, dtype[floating]]

inverse() SO3[source]#

Computes the inverse of our transform.

Returns:

Output.

Return type:

SO3

__matmul__(other: Self | ndarray[Any, dtype[floating]]) Self | ndarray[Any, dtype[floating]]#

Overload for the @ operator.

Switches between the group action (.apply()) and multiplication (.multiply()) based on the type of other.

Parameters:

other (Self | ndarray[Any, dtype[floating]]) –

Return type:

Self | ndarray[Any, dtype[floating]]

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,).

Return type:

Tuple[int, …]

matrix_dim: ClassVar[int] = 3#

Dimension of square matrix output from .as_matrix().

normalize() SO3[source]#

Normalize/projects values and returns.

Returns:

Normalized group member.

Return type:

SO3

parameters_dim: ClassVar[int] = 4#

Dimension of underlying parameters, .parameters().

space_dim: ClassVar[int] = 3#

Dimension of coordinates that can be transformed.

tangent_dim: ClassVar[int] = 3#

Dimension of tangent space.