Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Development branch, release 3.8.0 #302

Merged
merged 39 commits into from
Oct 28, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
39 commits
Select commit Hold shift + click to select a range
f532446
Fix Euler angle convention
AlexanderFabisch Oct 19, 2024
50c1325
Check if rotation matrix needs normalization
AlexanderFabisch Oct 19, 2024
210655b
Test function
AlexanderFabisch Oct 19, 2024
6c6a1c4
Add function to API docs
AlexanderFabisch Oct 19, 2024
6aa2916
Sort functions in API docs
AlexanderFabisch Oct 19, 2024
be3cd9e
Euler angle normalization
AlexanderFabisch Oct 19, 2024
6b208db
Link in user guide
AlexanderFabisch Oct 19, 2024
baa0bed
Fix test and function
AlexanderFabisch Oct 19, 2024
120853d
Add pr.euler_near_gimbal_lock
AlexanderFabisch Oct 19, 2024
620fe11
Add assert_euler_equal
AlexanderFabisch Oct 20, 2024
234ceb3
Test euler angle equality
AlexanderFabisch Oct 20, 2024
920cf93
Add compact_axis_angle_near_pi
AlexanderFabisch Oct 20, 2024
72093c1
Correct docstring
AlexanderFabisch Oct 20, 2024
b452a5a
Correct docstring
AlexanderFabisch Oct 20, 2024
3c6f08b
Add quaternion_double
AlexanderFabisch Oct 20, 2024
71dfdcc
Add quaternion_requires_renormalization
AlexanderFabisch Oct 20, 2024
90a6466
Add mrp_near_singularity
AlexanderFabisch Oct 21, 2024
69b3688
Add conversions between axis-angle and mrp
AlexanderFabisch Oct 21, 2024
845d2f6
Reorganize API docs for rotations
AlexanderFabisch Oct 21, 2024
1fd0cfa
Sort transformations API
AlexanderFabisch Oct 21, 2024
50fb5f6
Full branch coverage
AlexanderFabisch Oct 21, 2024
cd6a9f7
Add norm_mrp
AlexanderFabisch Oct 22, 2024
7967e47
Add mrp_double
AlexanderFabisch Oct 22, 2024
4f3bb57
Add assert_mrp_equal
AlexanderFabisch Oct 22, 2024
7e2580b
Add transform_requires_renormalization
AlexanderFabisch Oct 23, 2024
ea38dfe
Add assert_exponential_coordinates_equal
AlexanderFabisch Oct 23, 2024
1ca49eb
Fix "see also"
AlexanderFabisch Oct 23, 2024
5f6af9f
Add dual_quaternion_requires_renormalization
AlexanderFabisch Oct 25, 2024
361fd1f
Abbreviate dual quaternion symbol
AlexanderFabisch Oct 25, 2024
b6a8a4d
Add dual_quaternion_double
AlexanderFabisch Oct 25, 2024
373fc7e
More detailed explanation of dq double cover
AlexanderFabisch Oct 25, 2024
b13b3db
Rename private quaternion submodule
AlexanderFabisch Oct 25, 2024
b56b883
Fix import
AlexanderFabisch Oct 25, 2024
9907ec1
Structure API docs
AlexanderFabisch Oct 25, 2024
65c8e85
Reorganize batch API
AlexanderFabisch Oct 25, 2024
f4d3e80
Update feature list
AlexanderFabisch Oct 25, 2024
b807408
Link new functions in docs
AlexanderFabisch Oct 25, 2024
df678d9
Use S^3 for unit sphere
AlexanderFabisch Oct 28, 2024
143943b
Version 3.8.0
AlexanderFabisch Oct 28, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
474 changes: 253 additions & 221 deletions doc/source/api.rst

Large diffs are not rendered by default.

2 changes: 2 additions & 0 deletions doc/source/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,8 @@ pytransform3d offers...
translation / position
* conversions between those representations
* clear documentation of conventions
* functions to check for common pitfalls (e.g., singularities, ambiguities,
discontinuities)
* tight coupling with matplotlib to quickly visualize (or animate)
transformations
* the TransformManager which organizes complex chains of transformations
Expand Down
83 changes: 6 additions & 77 deletions doc/source/user_guide/euler_angles.rst
Original file line number Diff line number Diff line change
Expand Up @@ -71,10 +71,11 @@ and Cardan angles are usually restricted to

-\pi \leq \alpha < \pi, \qquad -\frac{\pi}{2} \leq \beta \leq \frac{\pi}{2}, \qquad -\pi \leq \gamma < \pi

to make these representations unique.
to make these representations unique (using
:func:`~pytransform3d.rotations.norm_euler`).

An alternative convention limits the range of :math:`\alpha` and :math:`\beta` to
:math:`\left[0, 2 \pi\right)`.
An alternative convention limits the range of :math:`\alpha` and :math:`\gamma`
to :math:`\left[0, 2 \pi\right)`.

-----------
Gimbal Lock
Expand All @@ -89,7 +90,8 @@ to an interval of length :math:`2\pi`: either all pairs of angles that
satisfy :math:`\alpha + \gamma = constant` or all pairs of angles
that satisfy :math:`\alpha - \gamma = constant`. When we reconstruct
Euler angles from a rotation matrix, we set one of these angles to 0 to
determine the other.
determine the other. We can check if Euler angles are close to gimbal lock
with :func:`~pytransform3d.rotations.euler_near_gimbal_lock`.

-----------
Other Names
Expand All @@ -100,79 +102,6 @@ xyz Cardan angles can also be called roll, pitch, and yaw (or sometimes
the intrinsic convention is used here as well). Roll is a rotation about
x, pitch is a rotation about y and yaw is a rotation about z.

---------------------------------------------------
API: Rotation Matrix / Quaternion from Euler Angles
---------------------------------------------------

.. currentmodule:: pytransform3d.rotations

.. autosummary::
:toctree: _apidoc/
:template: function.rst

~quaternion_from_euler
~matrix_from_euler
~active_matrix_from_intrinsic_euler_xzx
~active_matrix_from_extrinsic_euler_xzx
~active_matrix_from_intrinsic_euler_xyx
~active_matrix_from_extrinsic_euler_xyx
~active_matrix_from_intrinsic_euler_yxy
~active_matrix_from_extrinsic_euler_yxy
~active_matrix_from_intrinsic_euler_yzy
~active_matrix_from_extrinsic_euler_yzy
~active_matrix_from_intrinsic_euler_zyz
~active_matrix_from_extrinsic_euler_zyz
~active_matrix_from_intrinsic_euler_zxz
~active_matrix_from_extrinsic_euler_zxz
~active_matrix_from_intrinsic_euler_xzy
~active_matrix_from_extrinsic_euler_xzy
~active_matrix_from_intrinsic_euler_xyz
~active_matrix_from_extrinsic_euler_xyz
~active_matrix_from_intrinsic_euler_yxz
~active_matrix_from_extrinsic_euler_yxz
~active_matrix_from_intrinsic_euler_yzx
~active_matrix_from_extrinsic_euler_yzx
~active_matrix_from_intrinsic_euler_zyx
~active_matrix_from_extrinsic_euler_zyx
~active_matrix_from_intrinsic_euler_zxy
~active_matrix_from_extrinsic_euler_zxy
~active_matrix_from_extrinsic_roll_pitch_yaw

---------------------------------------------------
API: Euler Angles from Rotation Matrix / Quaternion
---------------------------------------------------

.. autosummary::
:toctree: _apidoc/
:template: function.rst

~euler_from_quaternion
~euler_from_matrix
~intrinsic_euler_xzx_from_active_matrix
~extrinsic_euler_xzx_from_active_matrix
~intrinsic_euler_xyx_from_active_matrix
~extrinsic_euler_xyx_from_active_matrix
~intrinsic_euler_yxy_from_active_matrix
~extrinsic_euler_yxy_from_active_matrix
~intrinsic_euler_yzy_from_active_matrix
~extrinsic_euler_yzy_from_active_matrix
~intrinsic_euler_zyz_from_active_matrix
~extrinsic_euler_zyz_from_active_matrix
~intrinsic_euler_zxz_from_active_matrix
~extrinsic_euler_zxz_from_active_matrix
~intrinsic_euler_xzy_from_active_matrix
~extrinsic_euler_xzy_from_active_matrix
~intrinsic_euler_xyz_from_active_matrix
~extrinsic_euler_xyz_from_active_matrix
~intrinsic_euler_yxz_from_active_matrix
~extrinsic_euler_yxz_from_active_matrix
~intrinsic_euler_yzx_from_active_matrix
~extrinsic_euler_yzx_from_active_matrix
~intrinsic_euler_zyx_from_active_matrix
~extrinsic_euler_zyx_from_active_matrix
~intrinsic_euler_zxy_from_active_matrix
~extrinsic_euler_zxy_from_active_matrix

----------
References
----------
Expand Down
2 changes: 1 addition & 1 deletion doc/source/user_guide/introduction.rst
Original file line number Diff line number Diff line change
Expand Up @@ -149,7 +149,7 @@ representations on the following pages.
| :math:`(\pmb{p}, \pmb{q})` | | | |
+----------------------------------------+---------------------+------------------+---------------+
| Dual quaternion | (8,) | X | X |
| :math:`\pmb{p} + \epsilon\pmb{q}` | | | |
| :math:`\boldsymbol{\sigma}` | | | |
+----------------------------------------+---------------------+------------------+---------------+

----------
Expand Down
37 changes: 24 additions & 13 deletions doc/source/user_guide/rotations.rst
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,10 @@ One of the most practical representations of orientation is a rotation matrix
Note that this is a non-minimal representation for orientations because we
have 9 values but only 3 degrees of freedom. This is because
:math:`\boldsymbol R` is orthonormal, which results in 6 constraints
(enforced with :func:`~pytransform3d.rotations.norm_matrix`):
(enforced with :func:`~pytransform3d.rotations.norm_matrix`
and checked with
:func:`~pytransform3d.rotations.matrix_requires_renormalization` or
:func:`~pytransform3d.rotations.check_matrix`):

* column vectors must have unit norm (3 constraints)
* and must be orthogonal to each other (3 constraints)
Expand Down Expand Up @@ -252,7 +255,9 @@ component-wise integration and differentiation with this representation.
**Cons**

* Ambiguities: an angle of 0 and any multiple of :math:`2\pi` represent
the same orientation; when :math:`\theta = \pi`, the axes
the same orientation (can be avoided with
:func:`~pytransform3d.rotations.norm_compact_axis_angle`, which introduces
discontinuities); when :math:`\theta = \pi`, the axes
:math:`\hat{\boldsymbol{\omega}}` and :math:`-\hat{\boldsymbol{\omega}}`
represent the same rotation.
* Supported operations: concatenation and transformation of vectors requires
Expand Down Expand Up @@ -309,7 +314,7 @@ Read `this paper <https://arxiv.org/pdf/1801.07478.pdf>`_ for details about
the two conventions and why Hamilton's convention should be used. Section VI A
gives further useful hints to identify which convention is used.

The unit quaternion space :math:`\mathbb{S}^3` can be used to represent
The unit quaternion space :math:`S^3` can be used to represent
orientations with an encoding based on the rotation axis and angle.
A rotation quaternion is a four-dimensional unit vector (versor)
:math:`\boldsymbol{\hat{q}}`.
Expand Down Expand Up @@ -347,9 +352,10 @@ functions :func:`~pytransform3d.rotations.quaternion_wxyz_from_xyzw` and
.. warning::

The *antipodal* unit quaternions :math:`\boldsymbol{\hat{q}}` and
:math:`-\boldsymbol{\hat{q}}` represent the same rotation (double cover).
This must be considered during operations like interpolation, distance
calculation, or (approximate) equality checks.
:math:`-\boldsymbol{\hat{q}}`
(:func:`~pytransform3d.rotations.quaternion_double`) represent the same
rotation (double cover). This must be considered during operations like
interpolation, distance calculation, or (approximate) equality checks.

The quaternion product
(:func:`~pytransform3d.rotations.concatenate_quaternions`) can be used to
Expand All @@ -369,8 +375,10 @@ with the quaternion product (:func:`~pytransform3d.rotations.q_prod_vector`).
**Pros**

* Representation: compact.
* Renormalization: cheap in comparison to rotation matrices;
less susceptible to round-off errors than matrix representation.
* Renormalization: checked with
:func:`~pytransform3d.rotations.quaternion_requires_renormalization`;
cheap in comparison to rotation matrices (); less susceptible to round-off
errors than matrix representation.
* Discontinuities: none.
* Computational efficiency: the quaternion product is cheaper than the matrix
product.
Expand Down Expand Up @@ -480,7 +488,8 @@ Another minimal representation of rotation are modified Rodrigues parameters

This representation is similar to the compact axis-angle representation.
However, the angle of rotation is converted to :math:`\tan(\frac{\theta}{4})`.
Hence, there is an easy conversion from unit quaternions to MRP:
Hence, there is an easy conversion from unit quaternions to MRP
(:func:`~pytransform3d.rotations.mrp_from_quaternion`):

.. math::

Expand All @@ -495,15 +504,17 @@ parameters.

.. warning::

MRPs have a singuarity at :math:`2 \pi` which we can avoid by ensuring the
angle of rotation does not exceed :math:`\pi`.
MRPs have a singuarity at :math:`2 \pi` (see
:func:`~pytransform3d.rotations.mrp_near_singularity`) which we can avoid
by ensuring the angle of rotation does not exceed :math:`\pi` (with
:func:`~pytransform3d.rotations.norm_mrp`).

.. warning::

MRPs have two representations for the same rotation:
:math:`\boldsymbol{\psi}` and :math:`-\frac{1}{||\boldsymbol{\psi}||^2}
\boldsymbol{\psi}` represent the same rotation and correspond to two
antipodal unit quaternions [8]_.
\boldsymbol{\psi}` (:func:`~pytransform3d.rotations.mrp_double`) represent
the same rotation and correspond to two antipodal unit quaternions [8]_.

**Pros**

Expand Down
11 changes: 6 additions & 5 deletions doc/source/user_guide/transformations.rst
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ another representation. The following table is an overview.
| :math:`(\pmb{p}, \pmb{q})` | | | | | |
+----------------------------------------+------------+--------------------------+---------------+---------------+-----------------+
| Dual quaternion | Quaternion | Yes | Yes | ScLERP | Required |
| :math:`\pmb{p} + \epsilon \pmb{q}` | Conjugate | | | | |
| :math:`\boldsymbol{\sigma}` | Conjugate | | | | |
+----------------------------------------+------------+--------------------------+---------------+---------------+-----------------+

---------------------
Expand Down Expand Up @@ -323,7 +323,8 @@ A dual quaternion consists of a real quaternion and a dual quaternion:

.. math::

\boldsymbol{p} + \epsilon \boldsymbol{q} = p_w + p_x i + p_y j + p_z k + \epsilon (q_w + q_x i + q_y j + q_z k),
\boldsymbol{\sigma} = \boldsymbol{p} + \epsilon \boldsymbol{q}
= p_w + p_x i + p_y j + p_z k + \epsilon (q_w + q_x i + q_y j + q_z k),

where :math:`\epsilon^2 = 0` and :math:`\epsilon \neq 0`.
We use unit dual quaternions to represent
Expand All @@ -345,9 +346,9 @@ interpolation between two dual quaternions is possible (with

.. warning::

The unit dual quaternions :math:`\boldsymbol{p} + \epsilon \boldsymbol{q}`
and :math:`-\boldsymbol{p} - \epsilon \boldsymbol{q}` represent exactly
the same transformation.
The unit dual quaternions
:math:`\boldsymbol{\sigma} = \boldsymbol{p} + \epsilon \boldsymbol{q}` and
:math:`-\boldsymbol{\sigma}` represent exactly the same transformation.

The reason for this ambiguity is that the real quaternion
:math:`\boldsymbol{p}` represents the orientation component, the dual
Expand Down
2 changes: 1 addition & 1 deletion pytransform3d/__init__.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
"""3D transformations for Python."""


__version__ = "3.7.0"
__version__ = "3.8.0"
37 changes: 28 additions & 9 deletions pytransform3d/rotations/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,9 @@
from ._utils import (
norm_angle, norm_vector, angle_between_vectors, perpendicular_to_vector,
vector_projection, perpendicular_to_vectors,
norm_axis_angle, norm_compact_axis_angle, norm_matrix,
norm_axis_angle, compact_axis_angle_near_pi, norm_compact_axis_angle,
matrix_requires_renormalization, norm_matrix,
quaternion_requires_renormalization,
plane_basis_from_normal,
check_skew_symmetric_matrix, check_matrix, check_quaternion,
check_quaternions, check_axis_angle, check_compact_axis_angle,
Expand All @@ -27,7 +29,8 @@
compact_axis_angle_from_matrix,
matrix_from_quaternion, matrix_from_compact_axis_angle,
matrix_from_axis_angle, matrix_from_two_vectors,
active_matrix_from_angle, matrix_from_euler,
active_matrix_from_angle, norm_euler, euler_near_gimbal_lock,
matrix_from_euler,
active_matrix_from_extrinsic_euler_xyx,
active_matrix_from_intrinsic_euler_xyx,
active_matrix_from_extrinsic_euler_xyz,
Expand Down Expand Up @@ -83,16 +86,19 @@
quaternion_from_angle,
cross_product_matrix,
mrp_from_quaternion,
quaternion_from_mrp)
from ._quaternion_operations import (
quaternion_integrate, quaternion_gradient, concatenate_quaternions, q_conj,
q_prod_vector, quaternion_diff, quaternion_dist, quaternion_from_euler)
from ._mrp import concatenate_mrp
quaternion_from_mrp,
mrp_from_axis_angle,
axis_angle_from_mrp)
from ._quaternions import (
quaternion_double, quaternion_integrate, quaternion_gradient,
concatenate_quaternions, q_conj, q_prod_vector, quaternion_diff,
quaternion_dist, quaternion_from_euler)
from ._mrp import mrp_near_singularity, norm_mrp, mrp_double, concatenate_mrp
from ._slerp import (slerp_weights, pick_closest_quaternion, quaternion_slerp,
axis_angle_slerp, rotor_slerp)
from ._testing import (
assert_quaternion_equal, assert_axis_angle_equal,
assert_compact_axis_angle_equal, assert_rotation_matrix)
assert_euler_equal, assert_quaternion_equal, assert_axis_angle_equal,
assert_compact_axis_angle_equal, assert_rotation_matrix, assert_mrp_equal)
from ._plot import plot_basis, plot_axis_angle, plot_bivector
from ._rotors import (
wedge, geometric_product, rotor_apply, rotor_reverse, concatenate_rotors,
Expand Down Expand Up @@ -121,8 +127,11 @@
"vector_projection",
"perpendicular_to_vectors",
"norm_axis_angle",
"compact_axis_angle_near_pi",
"norm_compact_axis_angle",
"matrix_requires_renormalization",
"norm_matrix",
"quaternion_requires_renormalization",
"random_vector",
"random_axis_angle",
"random_compact_axis_angle",
Expand Down Expand Up @@ -153,6 +162,8 @@
"matrix_from_axis_angle",
"matrix_from_two_vectors",
"active_matrix_from_angle",
"norm_euler",
"euler_near_gimbal_lock",
"matrix_from_euler",
"active_matrix_from_extrinsic_euler_xyx",
"active_matrix_from_intrinsic_euler_xyx",
Expand Down Expand Up @@ -208,10 +219,16 @@
"euler_from_quaternion",
"quaternion_from_angle",
"quaternion_from_euler",
"mrp_near_singularity",
"norm_mrp",
"mrp_double",
"concatenate_mrp",
"cross_product_matrix",
"mrp_from_quaternion",
"quaternion_from_mrp",
"mrp_from_axis_angle",
"axis_angle_from_mrp",
"quaternion_double",
"quaternion_integrate",
"quaternion_gradient",
"concatenate_quaternions",
Expand All @@ -223,10 +240,12 @@
"pick_closest_quaternion",
"quaternion_slerp",
"axis_angle_slerp",
"assert_euler_equal",
"assert_quaternion_equal",
"assert_axis_angle_equal",
"assert_compact_axis_angle_equal",
"assert_rotation_matrix",
"assert_mrp_equal",
"plot_basis",
"plot_axis_angle",
"wedge",
Expand Down
2 changes: 1 addition & 1 deletion pytransform3d/rotations/_constants.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,4 +17,4 @@
eps = 1e-7

two_pi = 2.0 * np.pi

half_pi = 0.5 * np.pi
Loading
Loading