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

[WIP] Improve documentation #292

Merged
merged 13 commits into from
Sep 18, 2024
11 changes: 0 additions & 11 deletions doc/source/user_guide/animations.rst

This file was deleted.

1 change: 0 additions & 1 deletion doc/source/user_guide/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -15,4 +15,3 @@ User Guide
transform_manager
transformation_over_time
camera
animations
2 changes: 2 additions & 0 deletions doc/source/user_guide/introduction.rst
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,8 @@ A (coordinate reference) frame in 3D Euclidean space is defined by an origin
a rigid body. The pose (position and orientation) of a rigid body (i.e., of
its frame) is always expressed with respect to another frame.

.. _Frame Notation:

--------------
Frame Notation
--------------
Expand Down
45 changes: 25 additions & 20 deletions doc/source/user_guide/rotations.rst
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,10 @@ SO(3): 3D Rotations
===================

The group of all rotations in the 3D Cartesian space is called :math:`SO(3)`
(SO: special orthogonal group). It is typically represented by 3D rotations
(SO: special orthogonal group). It is typically represented by 3D rotation
matrices [7]_. The minimum number of components that are required to describe
any rotation from :math:`SO(3)` is 3. However, there is no representation that
is non-redundant, continuous, and free of singularities. We will now take a
closer look at competing representations of rotations and the orientations they
can describe.
is non-redundant, continuous, and free of singularities.

Here is an overview of the representations and the conversions between them
that are available in pytransform3d.
Expand Down Expand Up @@ -125,14 +123,15 @@ This means that we rotate a point :math:`_B\boldsymbol{p}` by

This is called **linear map**.

Note that using our index notation and conventions the second index of the
rotation matrix and the left index of the point have to be the same. The
rotation is applied incorrectly if this is not the case.
Note that with our index notation (as explained in :ref:`Frame Notation`) and
these conventions, the second index of the rotation matrix and the left index
of the point have to be the same (:math:`B` in this example). The rotation is
applied incorrectly if this is not the case.

We can see that *each column* of such a rotation matrix is a basis vector
of frame :math:`A` with respect to frame :math:`B`.
We can plot the basis vectors of an orientation to visualize it.
Here, we can see orientation represented by the rotation matrix
*Each column* of a rotation matrix :math:`\boldsymbol{R}_{AB}` is a basis
vector of frame :math:`A` with respect to frame :math:`B`. We can plot the
basis vectors of an orientation to visualize it. Here, we can see orientation
represented by the rotation matrix

.. math::

Expand All @@ -141,7 +140,7 @@ Here, we can see orientation represented by the rotation matrix
1 & 0 & 0\\
0 & 1 & 0\\
0 & 0 & 1\\
\end{array} \right)
\end{array} \right).

.. plot::
:include-source:
Expand All @@ -151,7 +150,7 @@ Here, we can see orientation represented by the rotation matrix

.. note::

When plotting basis vectors it is a convention to use red for the x-axis,
When plotting basis vectors, it is a convention to use red for the x-axis,
green for the y-axis and blue for the z-axis (RGB for xyz).

We can easily chain multiple rotations: we can apply the rotation defined
Expand All @@ -162,7 +161,7 @@ by applying the rotation

\boldsymbol R_{AC} = \boldsymbol R_{AB} \boldsymbol R_{BC}.

Note that again the indices have to align. Otherwise rotations are not applied
Note that the indices have to align again. Otherwise rotations are not applied
in the correct order.

.. warning::
Expand Down Expand Up @@ -205,7 +204,7 @@ Axis-Angle

.. plot:: ../../examples/plots/plot_axis_angle.py

Each rotation can be represented by a single rotation around one axis.
Each rotation can be represented by a single rotation about one axis.
The axis can be represented as a three-dimensional unit vector and the angle
by a scalar:

Expand Down Expand Up @@ -335,10 +334,16 @@ typically we use the variable name q.
element and sometimes the last element of the versor. We will use
the first element to store the scalar component.

Since the other convention is also used often, pytransform3d provides the
functions :func:`~pytransform3d.rotations.quaternion_wxyz_from_xyzw` and
:func:`~pytransform3d.rotations.quaternion_xyzw_from_wxyz` for conversion.

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

**Pros**

Expand Down Expand Up @@ -405,12 +410,12 @@ more general as they can be extended to more dimensions [3]_ [4]_.
The concept of a quaternion builds on the axis-angle representation, in
which we rotate by an angle about a rotation axis (see black arrow in the
illustration above). The axis can be computed from the cross product of two
vectors (gray arrow). A rotor builds on a plane-angle representation, in which
vectors (gray arrows). A rotor builds on a plane-angle representation, in which
we rotate with a given direction by an angle in a plane (indicated by gray
area). The plane can be computed from the wedge product :math:`a \wedge b` of
two vectors :math:`a` and :math:`b`, which is a so-called bivector. Although
both approaches might seem different, in 3D they operate with exactly the same
numbers in exactly the same way.
area). The plane can be computed from the wedge product :math:`a \wedge b` (see
:func:`~pytransform3d.rotations.wedge`) of two vectors :math:`a` and :math:`b`,
which is a so-called bivector. Although both approaches might seem different,
in 3D they operate with exactly the same numbers in exactly the same way.

.. warning::

Expand Down
6 changes: 3 additions & 3 deletions doc/source/user_guide/transform_manager.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
========================
Managing Transformations
========================
=====================================
Organizing Transformations in a Graph
=====================================

It is sometimes very difficult to have an overview of all the transformations
that are required to calculate another transformation. Suppose you have
Expand Down
27 changes: 16 additions & 11 deletions doc/source/user_guide/transformation_ambiguities.rst
Original file line number Diff line number Diff line change
Expand Up @@ -37,9 +37,6 @@ communication to other software.
There are lots of ambiguities in the world of transformations. We try to
explain them all here.

.. contents:: :local:
:depth: 1

----------------------------------------------
Right-handed vs. Left-handed Coordinate System
----------------------------------------------
Expand Down Expand Up @@ -123,6 +120,9 @@ right-handed system and with the left hand in a left-handed system.
Active (Alibi) vs. Passive (Alias) Transformation
-------------------------------------------------

There are two different views of transformations: the active and the passive
view [1]_ [2]_.

.. image:: ../_static/active_passive.png
:alt: Passive vs. active transformation
:align: center
Expand All @@ -140,7 +140,7 @@ A passive transformation

* changes the coordinate system in which the object is described
* does not change the object
* could be used by physicists and engineers (e.g. roboticists)
* could be used by physicists and engineers (e.g., roboticists)

Another name for passive transformation is alias transformation.

Expand Down Expand Up @@ -274,7 +274,7 @@ frame.

</td>
</tr>
<table>
</table>

Using the inverse transformation in the active view gives us exactly the same
solution as the original transformation in the passive view and vice versa.
Expand Down Expand Up @@ -306,12 +306,6 @@ Its transformed version is usually used for a passive transformation:

The standard in pytransform3d is an active rotation.

Reference:

Selig, J.M.: Active Versus Passive Transformations in Robotics, 2006,
IEEE Robotics and Automation Magazine.
PDF: https://openresearch.lsbu.ac.uk/download/641fa36d365e0244b27dd2fc8b881a12061afe1eb5c3952bae15614d3d831710/185181/01598057.pdf.

----------------------------------------
Pre-multiply vs. Post-multiply Rotations
----------------------------------------
Expand Down Expand Up @@ -477,3 +471,14 @@ find when you combine different software systems.
(approach direction), x and y axes define the orientation
with which we approach the target
* Euler angles: extrinsic roll-pitch-yaw (xyz) convention

----------
References
----------

.. [1] Selig, J.M. (2006): Active Versus Passive Transformations in Robotics.
IEEE Robotics and Automation Magazine, 13(1), pp. 79-84, doi:
10.1109/MRA.2006.1598057. https://ieeexplore.ieee.org/document/1598057

.. [2] Wikipedia: Active and passive transformation.
https://en.wikipedia.org/wiki/Active_and_passive_transformation
6 changes: 3 additions & 3 deletions doc/source/user_guide/transformation_over_time.rst
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
==================================
Managing Transformations over Time
==================================
========================================
Graphs of Time-Dependent Transformations
========================================

In applications, where the transformations between coordinate frames are
dynamic (i.e. changing over time), consider using
Expand Down
39 changes: 25 additions & 14 deletions doc/source/user_guide/transformations.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
SE(3): 3D Transformations
=========================

The group of all proper rigid transformations (rototranslations) in the
The group of all proper rigid transformations (rototranslations) in
3D Cartesian space is :math:`SE(3)` (SE: special Euclidean group).
Transformations consist of a rotation and a translation. Those can be
represented in different ways just like rotations can be expressed
Expand All @@ -23,8 +23,8 @@ an analogous representation of transformations [1]_:
:math:`\left[\hat{\boldsymbol{\omega}}\right] \theta`.
* The **exponential coordinates** :math:`\mathcal{S} \theta` for rigid body
motions are similar to exponential coordinates
:math:`\hat{\boldsymbol{\omega}} \theta` for rotations (axis-angle
representation).
:math:`\hat{\boldsymbol{\omega}} \theta` for rotations (compact axis-angle
representation / rotation vector).
* A **twist** :math:`\mathcal V = \mathcal{S} \dot{\theta}` is similar to
angular velocity :math:`\hat{\boldsymbol{\omega}} \dot{\theta}`.
* A (unit) **dual quaternion**
Expand Down Expand Up @@ -91,22 +91,25 @@ It is possible to transform position vectors or direction vectors with it.
Position vectors are represented as a column vector
:math:`\left( x,y,z,1 \right)^T`.
This will activate the translation part of the transformation in a matrix
multiplication. When we transform a direction vector, we want to deactivate
the translation by setting the last component to zero:
multiplication (see :func:`~pytransform3d.transformations.vector_to_point`).
When we transform a direction vector, we want to deactivate the translation by
setting the last component to zero (see
:func:`~pytransform3d.transformations.vector_to_direction`):
:math:`\left( x,y,z,0 \right)^T`.

We can use a transformation matrix :math:`\boldsymbol T_{AB}` to transform a
point :math:`{_B}\boldsymbol{p}` from frame :math:`B` to frame :math:`A`.
For example, transforming a position vector :math:`p` will give the following
result:
point :math:`{_B}\boldsymbol{p}` from frame :math:`B` to frame :math:`A`:

.. math::

\boldsymbol{T}_{AB} {_B}\boldsymbol{p} =
\left( \begin{array}{c}
\boldsymbol{R} {_B}\boldsymbol{p} + \boldsymbol t\\
1\\
\end{array} \right)
\end{array} \right).

You can use :func:`~pytransform3d.transformations.transform` to apply a
transformation matrix to a homogeneous vector.

-----------------------
Position and Quaternion
Expand Down Expand Up @@ -190,7 +193,7 @@ coordinates of transformation and typically we use the variable name Stheta.
.. warning::

Note that we use the screw theory definition of exponential coordinates
and :math:`so(3)` (see next section) used by Paden (1985), Lynch and Park
and :math:`se(3)` (see next section) used by Paden (1985), Lynch and Park
(2017), and Corke (2017). They separate the parameter :math:`\theta` from
the screw axis. Additionally, they use the first three components to encode
rotation and the last three components to encode translation. There is an
Expand Down Expand Up @@ -263,15 +266,23 @@ A dual quaternion consists of a real quaternion and a dual quaternion:

\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`. We use unit dual quaternions to represent
where :math:`\epsilon^2 = 0` and :math:`\epsilon \neq 0`.
We use unit dual quaternions to represent
transformations. In this case, the real quaternion is a unit quaternion
and the dual quaternion is orthogonal to the real quaternion.
The real quaternion is used to represent the rotation and the dual
quaternion contains information about the rotation and translation.

Dual quaternions support similar operations as transformation matrices,
they can be renormalized efficiently, and interpolation between two
dual quaternions is possible.
Dual quaternions support similar operations as transformation matrices
(inversion through the conjugate of the two individual quaternions
:func:`~pytransform3d.transformations.dq_q_conj`, concatenation
through :func:`~pytransform3d.transformations.concatenate_dual_quaternions`,
and transformation of a point by
:func:`~pytransform3d.transformations.dq_prod_vector`),
they can be renormalized efficiently (with
:func:`~pytransform3d.transformations.check_dual_quaternion`, and
interpolation between two dual quaternions is possible (with
:func:`~pytransform3d.transformations.dual_quaternion_sclerp`).

.. warning::

Expand Down
4 changes: 3 additions & 1 deletion examples/animations/animate_rotation.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,9 @@
Animate Rotation
================

Animates a rotation about the x-axis.
Simple animations of frames and trajectories are easy to implement with
Matplotlib's FuncAnimation. The following example will generate a frame
that will be rotated about the x-axis.
"""
import numpy as np
import matplotlib.pyplot as plt
Expand Down
8 changes: 4 additions & 4 deletions examples/plots/plot_bivector.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,9 +22,9 @@

ax = pr.plot_basis()
pr.plot_bivector(ax=ax, a=a, b=b)
ax.view_init(azim=20, elev=20)
ax.set_xlim((0, 1))
ax.set_ylim((0, 1))
ax.set_zlim((0, 1))
ax.view_init(azim=75, elev=40)
ax.set_xlim((-0.5, 1))
ax.set_ylim((-0.5, 1))
ax.set_zlim((-0.5, 1))
plt.tight_layout()
plt.show()
3 changes: 2 additions & 1 deletion pytransform3d/rotations/_rotors.py
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,8 @@ def geometric_product(a, b):
r"""Geometric product of two vectors.

The geometric product consists of the symmetric inner / dot product and the
antisymmetric outer product of two vectors.
antisymmetric outer product (see :func:`~pytransform3d.rotations.wedge`) of
two vectors.

.. math::

Expand Down
Loading
Loading