mani_skill.utils.geometry.rotation_conversions#

Attributes#

Device

The transformation matrices returned from the functions in this file assume

Functions#

_angle_from_tan(axis, other_axis, data, horizontal, ...)

Extract the first or third Euler angle from the two members of

_axis_angle_rotation(axis, angle)

Return the rotation matrices for one of the rotations about an axis

_copysign(a, b)

Return a tensor where each element has the absolute value taken from the,

_index_from_letter(letter)

_sqrt_positive_part(x)

Returns torch.sqrt(torch.max(0, x))

axis_angle_to_matrix(axis_angle)

Convert rotations given as axis/angle to rotation matrices.

axis_angle_to_quaternion(axis_angle)

Convert rotations given as axis/angle to quaternions.

euler_angles_to_matrix(euler_angles, convention)

Convert rotations given as Euler angles in radians to rotation matrices.

matrix_to_axis_angle(matrix)

Convert rotations given as rotation matrices to axis/angle.

matrix_to_euler_angles(matrix, convention)

Convert rotations given as rotation matrices to Euler angles in radians.

matrix_to_quaternion(matrix)

Convert rotations given as rotation matrices to quaternions.

matrix_to_rotation_6d(matrix)

Converts rotation matrices to 6D rotation representation by Zhou et al. [1]

quaternion_apply(quaternion, point)

Apply the rotation given by a quaternion to a 3D point.

quaternion_invert(quaternion)

Given a quaternion representing rotation, get the quaternion representing

quaternion_multiply(a, b)

Multiply two quaternions representing rotations, returning the quaternion

quaternion_raw_multiply(a, b)

Multiply two quaternions.

quaternion_to_axis_angle(quaternions)

Convert rotations given as quaternions to axis/angle.

quaternion_to_matrix(quaternions)

Convert rotations given as quaternions to rotation matrices.

random_quaternions(n[, dtype, device])

Generate random quaternions representing rotations,

random_rotation([dtype, device])

Generate a single random 3x3 rotation matrix.

random_rotations(n[, dtype, device])

Generate random rotations as 3x3 rotation matrices.

rotation_6d_to_matrix(d6)

Converts 6D rotation representation by Zhou et al. [1] to rotation matrix

standardize_quaternion(quaternions)

Convert a unit quaternion to a standard form: one in which the real

Module Contents#

mani_skill.utils.geometry.rotation_conversions._angle_from_tan(axis, other_axis, data, horizontal, tait_bryan)[source]#

Extract the first or third Euler angle from the two members of the matrix which are positive constant times its sine and cosine.

Parameters:
  • axis (str) – Axis label “X” or “Y or “Z” for the angle we are finding.

  • other_axis (str) – Axis label “X” or “Y or “Z” for the middle axis in the convention.

  • data – Rotation matrices as tensor of shape (…, 3, 3).

  • horizontal (bool) – Whether we are looking for the angle for the third axis, which means the relevant entries are in the same row of the rotation matrix. If not, they are in the same column.

  • tait_bryan (bool) – Whether the first and third axes in the convention differ.

Returns:

Euler Angles in radians for each matrix in data as a tensor of shape (…).

Return type:

torch.Tensor

mani_skill.utils.geometry.rotation_conversions._axis_angle_rotation(axis, angle)[source]#

Return the rotation matrices for one of the rotations about an axis of which Euler angles describe, for each value of the angle given.

Parameters:
  • axis (str) – Axis label “X” or “Y or “Z”.

  • angle (torch.Tensor) – any shape tensor of Euler angles in radians

Returns:

Rotation matrices as tensor of shape (…, 3, 3).

Return type:

torch.Tensor

mani_skill.utils.geometry.rotation_conversions._copysign(a, b)[source]#

Return a tensor where each element has the absolute value taken from the, corresponding element of a, with sign taken from the corresponding element of b. This is like the standard copysign floating-point operation, but is not careful about negative 0 and NaN.

Parameters:
  • a (torch.Tensor) – source tensor.

  • b (torch.Tensor) – tensor whose signs will be used, of the same shape as a.

Returns:

Tensor of the same shape as a with the signs of b.

Return type:

torch.Tensor

mani_skill.utils.geometry.rotation_conversions._index_from_letter(letter)[source]#
Parameters:

letter (str) –

Return type:

int

mani_skill.utils.geometry.rotation_conversions._sqrt_positive_part(x)[source]#

Returns torch.sqrt(torch.max(0, x)) but with a zero subgradient where x is 0.

Parameters:

x (torch.Tensor) –

Return type:

torch.Tensor

mani_skill.utils.geometry.rotation_conversions.axis_angle_to_matrix(axis_angle)[source]#

Convert rotations given as axis/angle to rotation matrices.

Parameters:

axis_angle (torch.Tensor) – Rotations given as a vector in axis angle form, as a tensor of shape (…, 3), where the magnitude is the angle turned anticlockwise in radians around the vector’s direction.

Returns:

Rotation matrices as tensor of shape (…, 3, 3).

Return type:

torch.Tensor

mani_skill.utils.geometry.rotation_conversions.axis_angle_to_quaternion(axis_angle)[source]#

Convert rotations given as axis/angle to quaternions.

Parameters:

axis_angle (torch.Tensor) – Rotations given as a vector in axis angle form, as a tensor of shape (…, 3), where the magnitude is the angle turned anticlockwise in radians around the vector’s direction.

Returns:

quaternions with real part first, as tensor of shape (…, 4).

Return type:

torch.Tensor

mani_skill.utils.geometry.rotation_conversions.euler_angles_to_matrix(euler_angles, convention)[source]#

Convert rotations given as Euler angles in radians to rotation matrices.

Parameters:
  • euler_angles (torch.Tensor) – Euler angles in radians as tensor of shape (…, 3).

  • convention (str) – Convention string of three uppercase letters from {“X”, “Y”, and “Z”}.

Returns:

Rotation matrices as tensor of shape (…, 3, 3).

Return type:

torch.Tensor

mani_skill.utils.geometry.rotation_conversions.matrix_to_axis_angle(matrix)[source]#

Convert rotations given as rotation matrices to axis/angle.

Parameters:

matrix (torch.Tensor) – Rotation matrices as tensor of shape (…, 3, 3).

Returns:

Rotations given as a vector in axis angle form, as a tensor

of shape (…, 3), where the magnitude is the angle turned anticlockwise in radians around the vector’s direction.

Return type:

torch.Tensor

mani_skill.utils.geometry.rotation_conversions.matrix_to_euler_angles(matrix, convention)[source]#

Convert rotations given as rotation matrices to Euler angles in radians.

Parameters:
  • matrix (torch.Tensor) – Rotation matrices as tensor of shape (…, 3, 3).

  • convention (str) – Convention string of three uppercase letters.

Returns:

Euler angles in radians as tensor of shape (…, 3).

Return type:

torch.Tensor

mani_skill.utils.geometry.rotation_conversions.matrix_to_quaternion(matrix)[source]#

Convert rotations given as rotation matrices to quaternions.

Parameters:

matrix (torch.Tensor) – Rotation matrices as tensor of shape (…, 3, 3).

Returns:

quaternions with real part first, as tensor of shape (…, 4).

Return type:

torch.Tensor

mani_skill.utils.geometry.rotation_conversions.matrix_to_rotation_6d(matrix)[source]#

Converts rotation matrices to 6D rotation representation by Zhou et al. [1] by dropping the last row. Note that 6D representation is not unique. :param matrix: batch of rotation matrices of size (*, 3, 3)

Returns:

6D rotation representation, of size (*, 6)

Parameters:

matrix (torch.Tensor) –

Return type:

torch.Tensor

[1] Zhou, Y., Barnes, C., Lu, J., Yang, J., & Li, H. On the Continuity of Rotation Representations in Neural Networks. IEEE Conference on Computer Vision and Pattern Recognition, 2019. Retrieved from http://arxiv.org/abs/1812.07035

mani_skill.utils.geometry.rotation_conversions.quaternion_apply(quaternion, point)[source]#

Apply the rotation given by a quaternion to a 3D point. Usual torch rules for broadcasting apply.

Parameters:
  • quaternion (torch.Tensor) – Tensor of quaternions, real part first, of shape (…, 4).

  • point (torch.Tensor) – Tensor of 3D points of shape (…, 3).

Returns:

Tensor of rotated points of shape (…, 3).

Return type:

torch.Tensor

mani_skill.utils.geometry.rotation_conversions.quaternion_invert(quaternion)[source]#

Given a quaternion representing rotation, get the quaternion representing its inverse.

Parameters:

quaternion (torch.Tensor) – Quaternions as tensor of shape (…, 4), with real part first, which must be versors (unit quaternions).

Returns:

The inverse, a tensor of quaternions of shape (…, 4).

Return type:

torch.Tensor

mani_skill.utils.geometry.rotation_conversions.quaternion_multiply(a, b)[source]#

Multiply two quaternions representing rotations, returning the quaternion representing their composition, i.e. the versor with nonnegative real part. Usual torch rules for broadcasting apply.

Parameters:
  • a (torch.Tensor) – Quaternions as tensor of shape (…, 4), real part first.

  • b (torch.Tensor) – Quaternions as tensor of shape (…, 4), real part first.

Returns:

The product of a and b, a tensor of quaternions of shape (…, 4).

Return type:

torch.Tensor

mani_skill.utils.geometry.rotation_conversions.quaternion_raw_multiply(a, b)[source]#

Multiply two quaternions. Usual torch rules for broadcasting apply.

Parameters:
  • a (torch.Tensor) – Quaternions as tensor of shape (…, 4), real part first.

  • b (torch.Tensor) – Quaternions as tensor of shape (…, 4), real part first.

Returns:

The product of a and b, a tensor of quaternions shape (…, 4).

Return type:

torch.Tensor

mani_skill.utils.geometry.rotation_conversions.quaternion_to_axis_angle(quaternions)[source]#

Convert rotations given as quaternions to axis/angle.

Parameters:

quaternions (torch.Tensor) – quaternions with real part first, as tensor of shape (…, 4).

Returns:

Rotations given as a vector in axis angle form, as a tensor

of shape (…, 3), where the magnitude is the angle turned anticlockwise in radians around the vector’s direction.

Return type:

torch.Tensor

mani_skill.utils.geometry.rotation_conversions.quaternion_to_matrix(quaternions)[source]#

Convert rotations given as quaternions to rotation matrices.

Parameters:

quaternions (torch.Tensor) – quaternions with real part first, as tensor of shape (…, 4).

Returns:

Rotation matrices as tensor of shape (…, 3, 3).

Return type:

torch.Tensor

mani_skill.utils.geometry.rotation_conversions.random_quaternions(n, dtype=None, device=None)[source]#

Generate random quaternions representing rotations, i.e. versors with nonnegative real part.

Parameters:
  • n (int) – Number of quaternions in a batch to return.

  • dtype (Optional[torch.dtype]) – Type to return.

  • device (Optional[Device]) – Desired device of returned tensor. Default: uses the current device for the default tensor type.

Returns:

Quaternions as tensor of shape (N, 4).

Return type:

torch.Tensor

mani_skill.utils.geometry.rotation_conversions.random_rotation(dtype=None, device=None)[source]#

Generate a single random 3x3 rotation matrix.

Parameters:
  • dtype (Optional[torch.dtype]) – Type to return

  • device (Optional[Device]) – Device of returned tensor. Default: if None, uses the current device for the default tensor type

Returns:

Rotation matrix as tensor of shape (3, 3).

Return type:

torch.Tensor

mani_skill.utils.geometry.rotation_conversions.random_rotations(n, dtype=None, device=None)[source]#

Generate random rotations as 3x3 rotation matrices.

Parameters:
  • n (int) – Number of rotation matrices in a batch to return.

  • dtype (Optional[torch.dtype]) – Type to return.

  • device (Optional[Device]) – Device of returned tensor. Default: if None, uses the current device for the default tensor type.

Returns:

Rotation matrices as tensor of shape (n, 3, 3).

Return type:

torch.Tensor

mani_skill.utils.geometry.rotation_conversions.rotation_6d_to_matrix(d6)[source]#

Converts 6D rotation representation by Zhou et al. [1] to rotation matrix using Gram–Schmidt orthogonalization per Section B of [1]. :param d6: 6D rotation representation, of size (*, 6)

Returns:

batch of rotation matrices of size (*, 3, 3)

Parameters:

d6 (torch.Tensor) –

Return type:

torch.Tensor

[1] Zhou, Y., Barnes, C., Lu, J., Yang, J., & Li, H. On the Continuity of Rotation Representations in Neural Networks. IEEE Conference on Computer Vision and Pattern Recognition, 2019. Retrieved from http://arxiv.org/abs/1812.07035

mani_skill.utils.geometry.rotation_conversions.standardize_quaternion(quaternions)[source]#

Convert a unit quaternion to a standard form: one in which the real part is non negative.

Parameters:

quaternions (torch.Tensor) – Quaternions with real part first, as tensor of shape (…, 4).

Returns:

Standardized quaternions as tensor of shape (…, 4).

Return type:

torch.Tensor

mani_skill.utils.geometry.rotation_conversions.Device[source]#

The transformation matrices returned from the functions in this file assume the points on which the transformation will be applied are column vectors. i.e. the R matrix is structured as

R = [

[Rxx, Rxy, Rxz], [Ryx, Ryy, Ryz], [Rzx, Rzy, Rzz],

] # (3, 3)

This matrix can be applied to column vectors by post multiplication by the points e.g.

points = [[0], [1], [2]] # (3 x 1) xyz coordinates of a point transformed_points = R * points

To apply the same matrix to points which are row vectors, the R matrix can be transposed and pre multiplied by the points:

e.g.

points = [[0, 1, 2]] # (1 x 3) xyz coordinates of a point transformed_points = points * R.transpose(1, 0)