Homogeneous Transformation Matrices and Quaternions
Axis-Angle Representation¶
Axis-angle rotations
-
baldor.axis_angle.
to_euler
(axis, angle, axes='sxyz')[source]¶ Return Euler angles from a rotation in the axis-angle representation.
Parameters: - axis (array_like) – axis around which the rotation occurs
- angle (float) – angle of rotation
- axes (str, optional) – Axis specification; one of 24 axis sequences as string or encoded tuple
Returns: - ai (float) – First rotation angle (according to axes).
- aj (float) – Second rotation angle (according to axes).
- ak (float) – Third rotation angle (according to axes).
-
baldor.axis_angle.
to_quaternion
(axis, angle, isunit=False)[source]¶ Return quaternion from a rotation in the axis-angle representation.
Parameters: - axis (array_like) – axis around which the rotation occurs
- angle (float) – angle of rotation
Returns: q – Quaternion in w, x, y z (real, then vector) format
Return type: array_like
Notes
Quaternions \(w + ix + jy + kz\) are represented as \([w, x, y, z]\).
-
baldor.axis_angle.
to_transform
(axis, angle, point=None)[source]¶ Return homogeneous transformation from an axis-angle rotation.
Parameters: - axis (array_like) – axis around which the rotation occurs
- angle (float) – angle of rotation
- point (array_like) – point around which the rotation is performed
Returns: T – Homogeneous transformation (4x4)
Return type: array_like
Euler Angles¶
Generic Euler rotations
-
baldor.euler.
to_axis_angle
(ai, aj, ak, axes='sxyz')[source]¶ Return axis-angle rotation from Euler angles and axes sequence
Parameters: Returns: - axis (array_like) – axis around which rotation occurs
- angle (float) – angle of rotation
Examples
>>> import numpy as np >>> import baldor as br >>> axis, angle = br.euler.to_axis_angle(0, 1.5, 0, 'szyx') >>> np.allclose(axis, [0, 1, 0]) True >>> angle 1.5
-
baldor.euler.
to_quaternion
(ai, aj, ak, axes='sxyz')[source]¶ Returns a quaternion from Euler angles and axes sequence
Parameters: Returns: q – Quaternion in w, x, y z (real, then vector) format
Return type: array_like
Notes
Quaternions \(w + ix + jy + kz\) are represented as \([w, x, y, z]\).
Examples
>>> import numpy as np >>> import baldor as br >>> q = br.euler.to_quaternion(1, 2, 3, 'ryxz') >>> np.allclose(q, [0.435953, 0.310622, -0.718287, 0.444435]) True
-
baldor.euler.
to_transform
(ai, aj, ak, axes='sxyz')[source]¶ Return homogeneous transformation matrix from Euler angles and axes sequence.
Parameters: Returns: T – Homogeneous transformation (4x4)
Return type: array_like
Examples
>>> import numpy as np >>> import baldor as br >>> T = br.euler.to_transform(1, 2, 3, 'syxz') >>> np.allclose(np.sum(T[0]), -1.34786452) True >>> T = br.euler.to_transform(1, 2, 3, (0, 1, 0, 1)) >>> np.allclose(np.sum(T[0]), -0.383436184) True
Quaternions¶
Functions to operate quaternions.
Important
Quaternions \(w + ix + jy + kz\) are represented as \([w, x, y, z]\).
-
baldor.quaternion.
are_equal
(q1, q2, rtol=1e-05, atol=1e-08)[source]¶ Returns True if two quaternions are equal within a tolerance.
Parameters: Returns: equal – True if q1 and q2 are almost equal, False otherwise
Return type: See also
numpy.allclose()
- Contains the details about the tolerance parameters
Notes
Quaternions \(w + ix + jy + kz\) are represented as \([w, x, y, z]\).
Examples
>>> import baldor as br >>> q1 = [1, 0, 0, 0] >>> br.quaternion.are_equal(q1, [0, 1, 0, 0]) False >>> br.quaternion.are_equal(q1, [1, 0, 0, 0]) True >>> br.quaternion.are_equal(q1, [-1, 0, 0, 0]) True
-
baldor.quaternion.
conjugate
(q)[source]¶ Compute the conjugate of a quaternion.
Parameters: q (array_like) – Input quaternion (4 element sequence) Returns: qconj – The conjugate of the input quaternion. Return type: ndarray Notes
Quaternions \(w + ix + jy + kz\) are represented as \([w, x, y, z]\).
Examples
>>> import baldor as br >>> q0 = br.quaternion.random() >>> q1 = br.quaternion.conjugate(q0) >>> q1[0] == q0[0] and all(q1[1:] == -q0[1:]) True
-
baldor.quaternion.
dual_to_transform
(qr, qt)[source]¶ Return a homogeneous transformation from the given dual quaternion.
Parameters: - qr (array_like) – Input quaternion for the rotation component (4 element sequence)
- qt (array_like) – Input quaternion for the translation component (4 element sequence)
Returns: T – Homogeneous transformation (4x4)
Return type: array_like
Notes
Some literature prefers to use \(q\) for the rotation component and \(q'\) for the translation component
-
baldor.quaternion.
inverse
(q)[source]¶ Return multiplicative inverse of a quaternion
Parameters: q (array_like) – Input quaternion (4 element sequence) Returns: qinv – The inverse of the input quaternion. Return type: ndarray Notes
Quaternions \(w + ix + jy + kz\) are represented as \([w, x, y, z]\).
-
baldor.quaternion.
multiply
(q1, q2)[source]¶ Multiply two quaternions
Parameters: - q1 (array_like) – First input quaternion (4 element sequence)
- q2 (array_like) – Second input quaternion (4 element sequence)
Returns: result – The resulting quaternion
Return type: ndarray
Notes
Hamilton product of quaternions
Quaternions \(w + ix + jy + kz\) are represented as \([w, x, y, z]\).
Examples
>>> import numpy as np >>> import baldor as br >>> q = br.quaternion.multiply([4, 1, -2, 3], [8, -5, 6, 7]) >>> np.allclose(q, [28, -44, -14, 48]) True
-
baldor.quaternion.
norm
(q)[source]¶ Compute quaternion norm
Parameters: q (array_like) – Input quaternion (4 element sequence) Returns: n – quaternion norm Return type: float Notes
Quaternions \(w + ix + jy + kz\) are represented as \([w, x, y, z]\).
-
baldor.quaternion.
random
(rand=None)[source]¶ Generate an uniform random unit quaternion.
Parameters: rand (array_like or None) – Three independent random variables that are uniformly distributed between 0 and 1. Returns: qrand – The random quaternion Return type: array_like Notes
Quaternions \(w + ix + jy + kz\) are represented as \([w, x, y, z]\).
Examples
>>> import numpy as np >>> import baldor as br >>> q = br.quaternion.random() >>> np.allclose(1, np.linalg.norm(q)) True
-
baldor.quaternion.
to_axis_angle
(quaternion, identity_thresh=None)[source]¶ Return axis-angle rotation from a quaternion
Parameters: - quaternion (array_like) – Input quaternion (4 element sequence)
- identity_thresh (None or scalar, optional) – Threshold below which the norm of the vector part of the quaternion (x, y, z) is deemed to be 0, leading to the identity rotation. None (the default) leads to a threshold estimated based on the precision of the input.
Returns: - axis (array_like) – axis around which rotation occurs
- angle (float) – angle of rotation
Notes
Quaternions \(w + ix + jy + kz\) are represented as \([w, x, y, z]\). A quaternion for which x, y, z are all equal to 0, is an identity rotation. In this case we return a angle=0 and axis=[1, 0, 0]`. This is an arbitrary vector.
Examples
>>> import numpy as np >>> import baldor as br >>> axis, angle = br.euler.to_axis_angle(0, 1.5, 0, 'szyx') >>> np.allclose(axis, [0, 1, 0]) True >>> angle 1.5
-
baldor.quaternion.
to_euler
(quaternion, axes='sxyz')[source]¶ Return Euler angles from a quaternion using the specified axis sequence.
Parameters: - q (array_like) – Input quaternion (4 element sequence)
- axes (str, optional) – Axis specification; one of 24 axis sequences as string or encoded tuple
Returns: - ai (float) – First rotation angle (according to axes).
- aj (float) – Second rotation angle (according to axes).
- ak (float) – Third rotation angle (according to axes).
Notes
Many Euler angle triplets can describe the same rotation matrix Quaternions \(w + ix + jy + kz\) are represented as \([w, x, y, z]\).
Examples
>>> import numpy as np >>> import baldor as br >>> ai, aj, ak = br.quaternion.to_euler([0.99810947, 0.06146124, 0, 0]) >>> np.allclose([ai, aj, ak], [0.123, 0, 0]) True
-
baldor.quaternion.
to_transform
(quaternion)[source]¶ Return homogeneous transformation from a quaternion.
Parameters: - quaternion (array_like) – Input quaternion (4 element sequence)
- axes (str, optional) – Axis specification; one of 24 axis sequences as string or encoded tuple
Returns: T – Homogeneous transformation (4x4)
Return type: array_like
Notes
Quaternions \(w + ix + jy + kz\) are represented as \([w, x, y, z]\).
Examples
>>> import numpy as np >>> import baldor as br >>> T0 = br.quaternion.to_transform([1, 0, 0, 0]) # Identity quaternion >>> np.allclose(T0, np.eye(4)) True >>> T1 = br.quaternion.to_transform([0, 1, 0, 0]) # 180 degree rot around X >>> np.allclose(T1, np.diag([1, -1, -1, 1])) True
Homogeneous Transformations¶
Homogeneous Transformation Matrices
-
baldor.transform.
are_equal
(T1, T2, rtol=1e-05, atol=1e-08)[source]¶ Returns True if two homogeneous transformation are equal within a tolerance.
Parameters: Returns: equal – True if T1 and T2 are almost equal, False otherwise
Return type: See also
numpy.allclose()
- Contains the details about the tolerance parameters
-
baldor.transform.
between_axes
(axis_a, axis_b)[source]¶ Compute the transformation that aligns two vectors/axes.
Parameters: - axis_a (array_like) – The initial axis
- axis_b (array_like) – The goal axis
Returns: transform – The transformation that transforms axis_a into axis_b
Return type: array_like
-
baldor.transform.
inverse
(transform)[source]¶ Compute the inverse of an homogeneous transformation.
Note
This function is more efficient than
numpy.linalg.inv
given the special properties of homogeneous transformations.Parameters: transform (array_like) – The input homogeneous transformation Returns: inv – The inverse of the input homogeneous transformation Return type: array_like
-
baldor.transform.
random
(max_position=1.0)[source]¶ Generate a random homogeneous transformation.
Parameters: max_position (float, optional) – Maximum value for the position components of the transformation Returns: T – The random homogeneous transformation Return type: array_like Examples
>>> import numpy as np >>> import baldor as br >>> T = br.transform.random() >>> Tinv = br.transform.inverse(T) >>> np.allclose(np.dot(T, Tinv), np.eye(4)) True
-
baldor.transform.
to_axis_angle
(transform)[source]¶ Return rotation angle and axis from rotation matrix.
Parameters: transform (array_like) – The input homogeneous transformation Returns: - axis (array_like) – axis around which rotation occurs
- angle (float) – angle of rotation
- point (array_like) – point around which the rotation is performed
Examples
>>> import numpy as np >>> import baldor as br >>> axis = np.random.sample(3) - 0.5 >>> angle = (np.random.sample(1) - 0.5) * (2*np.pi) >>> point = np.random.sample(3) - 0.5 >>> T0 = br.axis_angle.to_transform(axis, angle, point) >>> axis, angle, point = br.transform.to_axis_angle(T0) >>> T1 = br.axis_angle.to_transform(axis, angle, point) >>> br.transform.are_equal(T0, T1) True
-
baldor.transform.
to_dual_quaternion
(transform)[source]¶ Return quaternion from the rotation part of an homogeneous transformation.
Parameters: - transform (array_like) – Rotation matrix. It can be (3x3) or (4x4)
- isprecise (bool) – If True, the input transform is assumed to be a precise rotation matrix and a faster algorithm is used.
Returns: - qr (array_like) – Quaternion in w, x, y z (real, then vector) for the rotation component
- qt (array_like) – Quaternion in w, x, y z (real, then vector) for the translation component
Notes
Some literature prefers to use \(q\) for the rotation component and \(q'\) for the translation component
-
baldor.transform.
to_euler
(transform, axes='sxyz')[source]¶ Return Euler angles from transformation matrix with the specified axis sequence.
Parameters: - transform (array_like) – Rotation matrix. It can be (3x3) or (4x4)
- axes (str, optional) – Axis specification; one of 24 axis sequences as string or encoded tuple
Returns: - ai (float) – First rotation angle (according to axes).
- aj (float) – Second rotation angle (according to axes).
- ak (float) – Third rotation angle (according to axes).
Notes
Many Euler angle triplets can describe the same rotation matrix
Examples
>>> import numpy as np >>> import baldor as br >>> T0 = br.euler.to_transform(1, 2, 3, 'syxz') >>> al, be, ga = br.transform.to_euler(T0, 'syxz') >>> T1 = br.euler.to_transform(al, be, ga, 'syxz') >>> np.allclose(T0, T1) True
-
baldor.transform.
to_quaternion
(transform, isprecise=False)[source]¶ Return quaternion from the rotation part of an homogeneous transformation.
Parameters: - transform (array_like) – Rotation matrix. It can be (3x3) or (4x4)
- isprecise (bool) – If True, the input transform is assumed to be a precise rotation matrix and a faster algorithm is used.
Returns: q – Quaternion in w, x, y z (real, then vector) format
Return type: array_like
Notes
Quaternions \(w + ix + jy + kz\) are represented as \([w, x, y, z]\).
Examples
>>> import numpy as np >>> import baldor as br >>> q = br.transform.to_quaternion(np.identity(4), isprecise=True) >>> np.allclose(q, [1, 0, 0, 0]) True >>> q = br.transform.to_quaternion(np.diag([1, -1, -1, 1])) >>> np.allclose(q, [0, 1, 0, 0]) or np.allclose(q, [0, -1, 0, 0]) True >>> T = br.axis_angle.to_transform((1, 2, 3), 0.123) >>> q = br.transform.to_quaternion(T, True) >>> np.allclose(q, [0.9981095, 0.0164262, 0.0328524, 0.0492786]) True
Vectors¶
Vector operations
-
baldor.vector.
norm
(vector)[source]¶ Return vector Euclidaan (L2) norm
Parameters: vector (array_like) – The input vector Returns: norm – The computed norm Return type: float Examples
>>> import numpy as np >>> import baldor as br >>> v = np.random.random(3) >>> n = br.vector.norm(v) >>> numpy.allclose(n, np.linalg.norm(v)) True
-
baldor.vector.
perpendicular
(vector)[source]¶ Find an arbitrary perpendicular vector
Parameters: vector (array_like) – The input vector Returns: result – The perpendicular vector Return type: array_like
-
baldor.vector.
skew
(vector)[source]¶ Returns the 3x3 skew matrix of the input vector.
The skew matrix is a square matrix R whose transpose is also its negative; that is, it satisfies the condition \(-R = R^T\).
Parameters: vector (array_like) – The input array Returns: R – The resulting 3x3 skew matrix Return type: array_like
-
baldor.vector.
transform_between_vectors
(vector_a, vector_b)[source]¶ Compute the transformation that aligns two vectors
Parameters: - vector_a (array_like) – The initial vector
- vector_b (array_like) – The goal vector
Returns: transform – The transformation between vector_a a vector_b
Return type: array_like
-
baldor.vector.
unit
(vector)[source]¶ Return vector divided by Euclidean (L2) norm
Parameters: vector (array_like) – The input vector Returns: unit – Vector divided by L2 norm Return type: array_like Examples
>>> import numpy as np >>> import baldor as br >>> v0 = np.random.random(3) >>> v1 = br.vector.unit(v0) >>> np.allclose(v1, v0 / np.linalg.norm(v0)) True