jaxlie._so3

Module Contents

Classes

SO3

Special orthogonal group for 3D rotations. Broadcasting rules are the same as

class jaxlie._so3.SO3(parameters)[source]

Bases: jaxlie.SOBase

Inheritance diagram of jaxlie.SO3

Special orthogonal group for 3D rotations. Broadcasting rules are the same as for numpy.

Internal parameterization is (qw, qx, qy, qz). Tangent parameterization is (omega_x, omega_y, omega_z). .. py:attribute:: wxyz

type:

jax.Array

Internal parameters. (w, x, y, z) quaternion. Shape should be (*, 4).

__repr__()[source]

Return repr(self).

Return type:

str

static from_x_radians(theta)[source]

Generates a x-axis rotation.

Parameters:
  • angle – X rotation, in radians.

  • theta (jaxlie.hints.Scalar) –

Returns:

Output.

Return type:

SO3

static from_y_radians(theta)[source]

Generates a y-axis rotation.

Parameters:
  • angle – Y rotation, in radians.

  • theta (jaxlie.hints.Scalar) –

Returns:

Output.

Return type:

SO3

static from_z_radians(theta)[source]

Generates a z-axis rotation.

Parameters:
  • angle – Z rotation, in radians.

  • theta (jaxlie.hints.Scalar) –

Returns:

Output.

Return type:

SO3

static from_rpy_radians(roll, pitch, yaw)[source]

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

Parameters:
  • roll (jaxlie.hints.Scalar) – X rotation, in radians. Applied first.

  • pitch (jaxlie.hints.Scalar) – Y rotation, in radians. Applied second.

  • yaw (jaxlie.hints.Scalar) – Z rotation, in radians. Applied last.

Returns:

Output.

Return type:

SO3

static from_quaternion_xyzw(xyzw)[source]

Construct a rotation from an xyzw quaternion.

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

Parameters:

xyzw (jaxlie.hints.Array) – xyzw quaternion. Shape should be (*, 4).

Returns:

Output.

Return type:

SO3

as_quaternion_xyzw()[source]

Grab parameters as xyzw quaternion.

Return type:

jax.Array

as_rpy_radians()[source]

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

Returns:

Named tuple containing Euler angles in radians.

Return type:

jaxlie.hints.RollPitchYaw

compute_roll_radians()[source]

Compute roll angle. Uses the ZYX mobile robot convention.

Returns:

Euler angle in radians.

Return type:

jax.Array

compute_pitch_radians()[source]

Compute pitch angle. Uses the ZYX mobile robot convention.

Returns:

Euler angle in radians.

Return type:

jax.Array

compute_yaw_radians()[source]

Compute yaw angle. Uses the ZYX mobile robot convention.

Returns:

Euler angle in radians.

Return type:

jax.Array

classmethod identity(batch_axes=())[source]

Returns identity element.

Parameters:

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

Returns:

Identity element.

Return type:

SO3

classmethod from_matrix(matrix)[source]

Get group member from matrix representation.

Parameters:

matrix (jaxlie.hints.Array) – Matrix representaiton.

Returns:

Group member.

Return type:

SO3

as_matrix()[source]

Get transformation as a matrix. Homogeneous for SE groups.

Return type:

jax.Array

parameters()[source]

Get underlying representation.

Return type:

jax.Array

apply(target)[source]

Applies group action to a point.

Parameters:

target (jaxlie.hints.Array) – Point to transform.

Returns:

Transformed point.

Return type:

jax.Array

multiply(other)[source]

Composes this transformation with another.

Returns:

self @ other

Parameters:

other (SO3) –

Return type:

SO3

classmethod exp(tangent)[source]

Computes expm(wedge(tangent)).

Parameters:

tangent (jaxlie.hints.Array) – Tangent vector to take the exponential of.

Returns:

Output.

Return type:

SO3

log()[source]

Computes vee(logm(transformation matrix)).

Returns:

Output. Shape should be (tangent_dim,).

Return type:

jax.Array

adjoint()[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:

jax.Array

inverse()[source]

Computes the inverse of our transform.

Returns:

Output.

Return type:

SO3

normalize()[source]

Normalize/projects values and returns.

Returns:

Normalized group member.

Return type:

SO3

classmethod sample_uniform(key, batch_axes=())[source]

Draw a uniform sample from the group. Translations (if applicable) are in the range [-1, 1].

Parameters:
  • key (jax.Array) – PRNG key, as returned by jax.random.PRNGKey().

  • batch_axes (jax_dataclasses.Static[Tuple[int, Ellipsis]]) – Any leading batch axes for the output transforms. Each sampled transform will be different.

Returns:

Sampled group member.

Return type:

SO3