Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
1 change: 0 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
<img src="https://raw.githubusercontent.com/dfki-ric/pytransform3d/main/doc/source/_static/logo.png" />

[![CircleCI](https://dl.circleci.com/status-badge/img/gh/dfki-ric/pytransform3d/tree/main.svg?style=svg)](https://dl.circleci.com/status-badge/redirect/gh/dfki-ric/pytransform3d/tree/main)
[![codecov](https://codecov.io/gh/dfki-ric/pytransform3d/branch/main/graph/badge.svg?token=jB10RM3Ujj)](https://codecov.io/gh/dfki-ric/pytransform3d)
[![Paper DOI](http://joss.theoj.org/papers/10.21105/joss.01159/status.svg)](https://doi.org/10.21105/joss.01159)
[![Release DOI](https://zenodo.org/badge/DOI/10.5281/zenodo.2553450.svg)](https://doi.org/10.5281/zenodo.2553450)
Expand Down
12 changes: 12 additions & 0 deletions doc/source/_static/custom.css
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
:root {
--pst-sidebar-width: 100px;
--pst-secondary-sidebar-width: 100px;
}

.bd-main .bd-content .bd-article-container {
max-width: 100%; /* Allows content to expand if sidebars are smaller */
}

.bd-page-width {
max-width: 100%; /* Ensures the overall page uses more width */
}
Binary file added doc/source/_static/overview.pdf
Binary file not shown.
Binary file added doc/source/_static/overview.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
165 changes: 165 additions & 0 deletions doc/source/_static/overview.tex
Original file line number Diff line number Diff line change
@@ -0,0 +1,165 @@
\documentclass{article}
\usepackage{amssymb,amsmath}
\usepackage[pdftex,active,tightpage]{preview}
\setlength\PreviewBorder{2mm}

% converted to png via
% pdflatex overview.tex
% pdftoppm -png overview.pdf > overview.png

\usepackage{tikz}
\usetikzlibrary{arrows, arrows.meta, positioning}

\begin{document}
\begin{preview}
\newcommand{\matx}{10.1}
\newcommand{\maty}{14.2}

\begin{tikzpicture}
\node[draw,shape=rectangle,rounded corners,fill=cyan!10] (legendconversionrot) at (7.5,18.7) {\large\texttt{pytransform3d.rotations}};

\node[draw,shape=rectangle,rounded corners,fill=blue!10] (legendconversiontr) at (21.5,18.7) {\large\texttt{pytransform3d.transformations}};

\node[draw,shape=rectangle,thick,rounded corners,fill=blue!15] (tmat) at (17,15) {\begin{minipage}{4cm}\textbf{transformation matrix}\\[0.3em]
$\boldsymbol{T} \in SE(3)$\\[0.3em]
\texttt{transform}\\[0.3em]
shape (4, 4)
\end{minipage}};

\node[draw,shape=rectangle,thick,rounded corners,fill=blue!15] (dquat) at (21.5,15) {\begin{minipage}{4cm}\textbf{(unit) dual quaternion}\\[0.3em]
$\boldsymbol{\sigma}$\\[0.3em]
\texttt{dual\_quaternion}\\[0.3em]
shape (8,)
\end{minipage}};

\node[draw,shape=rectangle,thick,rounded corners,fill=blue!15] (pq) at (26.5,15) {\begin{minipage}{5cm}\textbf{position and unit quaternion}\\[0.3em]
$(\boldsymbol{p}, \boldsymbol{q}) \in \mathbb{R}^3 \times S^3$\\[0.3em]
\texttt{pq}\\[0.3em]
shape (7,)
\end{minipage}};

\node[draw,shape=rectangle,thick,rounded corners,fill=blue!15] (logtr) at (17,11) {\begin{minipage}{4.9cm}\textbf{logarithm of transformation}\\[0.3em]
$\left[\mathcal{S}\right]\theta \in se(3)$\\[0.3em]
\texttt{transform\_log}\\[0.3em]
shape (4, 4)
\end{minipage}};

\node[draw,shape=rectangle,thick,rounded corners] (screwmat) at (22.5,11) {\begin{minipage}{3.8cm}\textbf{screw matrix}\\[0.3em]
$\left[\mathcal{S}\right] \in se(3)$\\[0.3em]
\texttt{screw\_matrix}\\[0.3em]
shape (4, 4)
\end{minipage}};

\node[draw,shape=rectangle,thick,rounded corners,fill=blue!15] (expcoord) at (17,7) {\begin{minipage}{7.5cm}\textbf{exponential coordinates of transformation}\\[0.3em]
$\mathcal{S}\theta \in \mathbb{R}^6$\\[0.3em]
\texttt{exponential\_coordinates}\\[0.3em]
shape (6,)
\end{minipage}};

\node[draw,shape=rectangle,thick,rounded corners] (spvel) at (24,7) {\begin{minipage}{4cm}\textbf{twist / spatial velocity}\\[0.3em]
$\mathcal{S}\dot{\theta} \in \mathbb{R}^6$\\[0.3em]
shape (6,)
\end{minipage}};

\node[draw,shape=rectangle,thick,rounded corners] (spacc) at (29,7) {\begin{minipage}{3.5cm}\textbf{spatial acceleration}\\[0.3em]
$\mathcal{S}\ddot{\theta} \in \mathbb{R}^6$\\[0.3em]
shape (6,)
\end{minipage}};

\node[draw,shape=rectangle,thick,rounded corners] (scrax) at (17,2) {\begin{minipage}{2.2cm}\textbf{screw axis}\\[0.3em]
$\mathcal{S} \in \mathbb{R}^6$\\[0.3em]
\texttt{screw\_axis}\\[0.3em]
shape (6,)
\end{minipage}};

\node[draw,shape=rectangle,thick,rounded corners] (screw) at (22,2) {\begin{minipage}{5.2cm}\textbf{screw parameters}\\[0.3em]
$(\boldsymbol{q}, \hat{\boldsymbol{s}}, h) \in \mathbb{R}^3 \times S^2 \times \mathbb{R}$\\[0.3em]
\texttt{screw\_parameters}\\[0.3em]
tuple[shape (3,), shape (3,), float]
\end{minipage}};

\draw[<->] (tmat) -- (logtr) node[midway,left] {exp./log. map};
\draw[->] (expcoord) -- (logtr) node[midway,left] {$\left[\cdot\right]$};
\draw[->] (expcoord) -- (spvel) node[midway,above] {$\frac{\partial \mathcal{S}\theta}{\partial t}$};
\draw[->] (spvel) -- (spacc) node[midway,above] {$\frac{\partial \mathcal{S}\dot{\theta}}{\partial t}$};
\draw[->] (scrax) -- (expcoord) node[midway,left] {$\theta$};
\draw[->] (screwmat) -- (logtr) node[midway,above] {$\theta$};
\draw[<->] (screw) -- (scrax) node[midway,above] {};

\draw [thick,rounded corners,fill=cyan!15] (\matx-0.2,\maty-0.5) rectangle (\matx+3.1,\maty+2.2);
\node[anchor=west] (rotmatname) at (\matx,\maty+1.8) {\textbf{rotation matrix}};
\node[anchor=west] (rotmatsymbol) at (\matx,\maty+1.2) {$\boldsymbol{R}$};
\node[anchor=west] (rotmatset) at (\matx+0.4,\maty+1.178) {$\in SO(3)$};
\node[anchor=west] (rotmatpname) at (\matx,\maty+0.6) {\texttt{matrix}};
\node[anchor=west] (rotmatarray) at (\matx,\maty) {shape (3, 3)};

\node (legendname) at (\matx-2,\maty+3) {representation};
\draw[red] (rotmatname) edge (legendname);
\node (legendsymbol) at (\matx-3,\maty+1.9) {mathematical symbol};
\draw[red] (rotmatsymbol) edge (legendsymbol);
\node (legendset) at (\matx+4,\maty+1.2) {set};
\draw[red] (rotmatset) edge (legendset);
\node (legendpname) at (\matx-3.3,\maty+0.7) {\begin{minipage}{3.1cm}\centering name in pytransform3d\end{minipage}};
\draw[red] (rotmatpname) edge (legendpname);
\node (legendarray) at (\matx-2,\maty-0.5) {NumPy array};
\draw[red] (rotmatarray) edge (legendarray);

\node[draw,shape=rectangle,thick,rounded corners,fill=cyan!15] (quat) at (1.8,15) {\begin{minipage}{6cm}\textbf{(unit) quaternion / versor / rotor}\\[0.3em]
$\boldsymbol{q} \in S^3$\\[0.3em]
\texttt{quaternion}\\[0.3em]
shape (4,)
\end{minipage}};

\node[draw,shape=rectangle,thick,rounded corners,fill=cyan!15] (logrot) at (11.2,11) {\begin{minipage}{3.8cm}\textbf{logarithm of rotation}\\[0.3em]
$\left[\boldsymbol{\omega}\right] \in so(3)$\\[0.3em]
\texttt{rot\_log}\\[0.3em]
shape (3, 3)
\end{minipage}};

\node[draw,shape=rectangle,thick,rounded corners,fill=cyan!15] (rotvec) at (11.2,7) {\begin{minipage}{3.3cm}\textbf{rotation vector}\\[0.3em]
$\boldsymbol{\omega} = \hat{\boldsymbol{\omega}}\theta \in \mathbb{R}^3$\\[0.3em]
\texttt{compact\_axis\_angle}\\[0.3em]
shape (3,)
\end{minipage}};

\node[draw,shape=rectangle,thick,rounded corners] (angvel) at (6.9,7) {\begin{minipage}{2.8cm}\textbf{angular velocity}\\[0.3em]
$\dot{\boldsymbol{\omega}} = \hat{\boldsymbol{\omega}}\dot{\theta} \in \mathbb{R}^3$\\[0.3em]
shape (3,)
\end{minipage}};

\node[draw,shape=rectangle,thick,rounded corners] (angacc) at (2.5,7) {\begin{minipage}{3.6cm}\textbf{angular acceleration}\\[0.3em]
$\hat{\boldsymbol{\omega}}\ddot{\theta} \in \mathbb{R}^3$\\[0.3em]
shape (3,)
\end{minipage}};

\node[draw,shape=rectangle,thick,rounded corners,fill=cyan!15] (axan) at (11.2,3.7) {\begin{minipage}{2.4cm}\textbf{axis-angle}\\[0.3em]
$(\hat{\boldsymbol{\omega}}, \theta) \in S^2 \times \mathbb{R}$\\[0.3em]
\texttt{axis\_angle}\\[0.3em]
shape (4,)
\end{minipage}};

\node[draw,shape=rectangle,thick,rounded corners] (rotax) at (11.2,1.5) {\begin{minipage}{3.8cm}\textbf{rotation axis}\\[0.3em]
$\hat{\boldsymbol{\omega}} \in S^2$
\end{minipage}};

\node[draw,shape=rectangle,thick,rounded corners,fill=cyan!15] (euler) at (3,1) {\begin{minipage}{7.5cm}\textbf{proper Euler / Cardan / Tait-Bryan angles}\\[0.3em]
$(\alpha, \beta, \gamma) \in \mathbb{R}^3$\\[0.3em]
\texttt{euler}\\[0.3em]
shape (3,)
\end{minipage}};

\node[draw,shape=rectangle,thick,rounded corners,fill=cyan!15] (mrp) at (6,3.7) {\begin{minipage}{5.6cm}\textbf{modified Rodrigues parameters}\\[0.3em]
$\boldsymbol{\psi} = \hat{\boldsymbol{\omega}} \tan{\frac{\theta}{4}} \in \mathbb{R}^3$\\[0.3em]
\texttt{mrp}\\[0.3em]
shape (3,)
\end{minipage}};

\draw[<->] (rotmatarray) -- (logrot) node[midway,left] {exp./log. map};
\draw[->] (rotvec) -- (logrot) node[midway,left] {cross product matrix};
\draw[->] (rotvec) -- (angvel) node[midway,above] {$\frac{\partial \boldsymbol{\omega}}{\partial t}$};
\draw[->] (angvel) -- (angacc) node[midway,above] {$\frac{\partial \dot{\boldsymbol{\omega}}}{\partial t}$};
\draw[->] (axan) -- (rotvec) node[midway,left] {product};
\draw[->] (rotax) -- (axan) node[midway,left] {$\theta$};
\end{tikzpicture}
\end{preview}
\end{document}
1 change: 1 addition & 0 deletions doc/source/conf.py
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,7 @@
"api": [],
}
html_static_path = ['_static']
html_css_files = ['custom.css']
html_last_updated_fmt = '%b %d, %Y'
html_use_smartypants = True
html_show_sourcelink = False
Expand Down
51 changes: 6 additions & 45 deletions doc/source/user_guide/introduction.rst
Original file line number Diff line number Diff line change
Expand Up @@ -104,53 +104,14 @@ representations.
We can use many different representations of rotation and / or translation.
Here is an overview of the representations that are available in pytransform3d.
All representations are stored in NumPy arrays, of which the corresponding
shape is shown in this table. You will find more details on these
shape is shown in this figure. You will find more details on these
representations on the following pages.

+----------------------------------------+---------------------+------------------+---------------+
| | | Rigid Transformation - SE(3) |
+ | +------------------+---------------+
| Representation and Mathematical Symbol | NumPy Array Shape | Rotation - SO(3) | Translation |
+========================================+=====================+==================+===============+
| Rotation matrix | (3, 3) | X | |
| :math:`\pmb{R}` | | | |
+----------------------------------------+---------------------+------------------+---------------+
| Axis-angle | (4,) | X | |
| :math:`(\hat{\pmb{\omega}}, \theta)` | | | |
+----------------------------------------+---------------------+------------------+---------------+
| Rotation vector | (3,) | X | |
| :math:`\pmb{\omega}` | | | |
+----------------------------------------+---------------------+------------------+---------------+
| Logarithm of rotation | (3, 3) | X | |
| :math:`\left[\pmb{\omega}\right]` | | | |
+----------------------------------------+---------------------+------------------+---------------+
| Quaternion | (4,) | X | |
| :math:`\pmb{q}` | | | |
+----------------------------------------+---------------------+------------------+---------------+
| Rotor | (4,) | X | |
| :math:`R` | | | |
+----------------------------------------+---------------------+------------------+---------------+
| Euler angles | (3,) | X | |
| :math:`(\alpha, \beta, \gamma)` | | | |
+----------------------------------------+---------------------+------------------+---------------+
| Modified Rodrigues parameters | (3,) | X | |
| :math:`\pmb{\psi}` | | | |
+----------------------------------------+---------------------+------------------+---------------+
| Transformation matrix | (4, 4) | X | X |
| :math:`\pmb{T}` | | | |
+----------------------------------------+---------------------+------------------+---------------+
| Exponential coordinates | (6,) | X | X |
| :math:`\mathcal{S}\theta` | | | |
+----------------------------------------+---------------------+------------------+---------------+
| Logarithm of transformation | (4, 4) | X | X |
| :math:`\left[\mathcal{S}\right]\theta` | | | |
+----------------------------------------+---------------------+------------------+---------------+
| Position and quaternion | (7,) | X | X |
| :math:`(\pmb{p}, \pmb{q})` | | | |
+----------------------------------------+---------------------+------------------+---------------+
| Dual quaternion | (8,) | X | X |
| :math:`\boldsymbol{\sigma}` | | | |
+----------------------------------------+---------------------+------------------+---------------+

.. figure:: ../_static/overview.png
:alt: Overview of representations for rotations and transformations in 3D.
:align: center
:width: 100%

----------
References
Expand Down
2 changes: 1 addition & 1 deletion pytransform3d/__init__.py
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
"""3D transformations for Python."""

__version__ = "3.14.1"
__version__ = "3.14.2"
34 changes: 15 additions & 19 deletions pytransform3d/transform_manager/_transform_graph_base.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
"""Common base class of transformation graphs."""

import abc
import copy

import numpy as np
import scipy.sparse as sp
Expand Down Expand Up @@ -319,27 +320,22 @@ def connected_components(self):
def check_consistency(self):
"""Check consistency of the known transformations.

The complexity of this is between :math:`O(n^2)` and :math:`O(n^3)`,
where :math:`n` is the number of nodes. In graphs where each pair of
nodes is directly connected the complexity is :math:`O(n^2)`. In graphs
that are actually paths, the complexity is :math:`O(n^3)`.
The computational cost of this operation is very high.

Returns
-------
consistent : bool
Is the graph consistent, i.e. is A2B always the same as the inverse
of B2A?
Is the graph consistent, i.e., if there are two ways of computing
A2B, do they give almost identical results?
"""
consistent = True
for node1 in self.nodes:
for node2 in self.nodes:
try:
node1_to_node2 = self.get_transform(node1, node2)
node2_to_node1 = self.get_transform(node2, node1)
node1_to_node2_inv = invert_transform(node2_to_node1)
consistent = consistent and np.allclose(
node1_to_node2, node1_to_node2_inv
)
except KeyError:
pass # Frames are not connected
return consistent
for (from_frame, to_frame), A2B in self.transforms.items():
clone = copy.deepcopy(self)
clone.remove_transform(from_frame, to_frame)
try:
A2B_from_path = clone.get_transform(from_frame, to_frame)
if not np.allclose(A2B, A2B_from_path):
return False
except KeyError:
# A2B cannot be computed in any other way
continue
return True