The transformations module

Numython R&D, (c) 2024 Moro is a Python library for kinematic and dynamic modeling of serial robots. This library has been designed, mainly, for academic and research purposes, using SymPy as base library.

moro.transformations.axa2rot(k, theta)[source]

Given a R^3 vector (k) and an angle (theta), return the SO(3) matrix associated.

moro.transformations.compose_rotations(*rotations)[source]

Composes rotation matrices w.r.t. fixed or movable frames

Parameters
:param rotations: A tuple that contains (angle, axis, frame, deg)
:type rotations: tuple
Returns
return

Rotation matrix ..

:rtype:class:sympy.matrices.dense.MutableDenseMatrix

Examples

>>> compose_rotations((45, "z", "fixed", True), (30, "x", "local", True))
⎡0.707106781186548  -0.612372435695794  0.353553390593274 ⎤
⎢                                                         ⎥
⎢0.707106781186547  0.612372435695795   -0.353553390593274⎥
⎢                                                         ⎥
⎣        0                 0.5          0.866025403784439 ⎦
moro.transformations.dh(a, alpha, d, theta)[source]

Calculates Denavit-Hartenberg matrix given the four parameters.

Parameters
:param a: DH parameter
:type a: int, float or symbol
:param alpha: DH parameter
:type alpha: int, float or symbol
:param d: DH parameter
:type d: int, float or symbol
:param theta: DH parameter
:type theta: int, float or symbol
Returns
return

Denavit-Hartenberg matrix (4x4) ..

:rtype:class:sympy.matrices.dense.MutableDenseMatrix

Examples

With numerical values:

>>> dh(100,pi/2,50,pi/2)
⎡0  0  1   0 ⎤
⎢            ⎥
⎢1  0  0  100⎥
⎢            ⎥
⎢0  1  0  50 ⎥
⎢            ⎥
⎣0  0  0   1 ⎦

Using symbolic values:

>>> a = symbols("a")
>>> t = symbols("t")
>>> dh(a,0,0,t)
⎡cos(t)  -sin(t)  0  a⋅cos(t)⎤
⎢                            ⎥
⎢sin(t)  cos(t)   0  a⋅sin(t)⎥
⎢                            ⎥
⎢  0        0     1     0    ⎥
⎢                            ⎥
⎣  0        0     0     1    ⎦
moro.transformations.eul2htm(phi, theta, psi, seq='zxz', deg=False)[source]

Given a set of Euler Angles (phi,theta,psi) for specific sequence this function returns the homogeneous transformation matrix associated. Default sequence is ZXZ.

Parameters
phi: int, float, symbol

First angle of the set

theta: int, float, symbol

Second angle of the set

psi: int, float, symbol

Third angle of the set

deg: bool

This parameter is True if phi, theta, and psi are given in degrees, by default it’s assumed to be False (angles in radians).

Returns
H: sympy.matrices.dense.MutableDenseMatrix

A homogeneous transformation matrix (SE(3)).

Examples

>>> eul2htm(90,90,90,"zxz",True)
⎡0  0   1  0⎤
⎢           ⎥
⎢0  -1  0  0⎥
⎢           ⎥
⎢1  0   0  0⎥
⎢           ⎥
⎣0  0   0  1⎦
>>> eul2htm(pi/2,pi/2,pi/2)
⎡0  0   1  0⎤
⎢           ⎥
⎢0  -1  0  0⎥
⎢           ⎥
⎢1  0   0  0⎥
⎢           ⎥
⎣0  0   0  1⎦
>>> eul2htm(0,pi/2,0,"zyz")
⎡0   0  1  0⎤
⎢           ⎥
⎢0   1  0  0⎥
⎢           ⎥
⎢-1  0  0  0⎥
⎢           ⎥
⎣0   0  0  1⎦
moro.transformations.eul2rot(phi, theta, psi, seq='zxz', deg=False)[source]
moro.transformations.htm2eul(H, seq='zxz', deg=False)[source]

Given a homogeneous transformation matrix this function return the equivalent set of Euler Angles.

If “deg” is True then Euler Angles are converted to degrees.

>>> H = htmrot(pi/3,"y")*htmrot(pi/4,"x")
>>> H
⎡      √6   √6    ⎤
⎢1/2   ──   ──   0⎥
⎢      4    4     ⎥
⎢                 ⎥
⎢      √2  -√2    ⎥
⎢ 0    ──  ────  0⎥
⎢      2    2     ⎥
⎢                 ⎥
⎢-√3   √2   √2    ⎥
⎢────  ──   ──   0⎥
⎢ 2    4    4     ⎥
⎢                 ⎥
⎣ 0    0    0    1⎦
>>> htm2eul(H)
⎛    ⎛√3⎞                     ⎞
⎜atan⎜──⎟, atan(√7), -atan(√6)⎟
⎝    ⎝2 ⎠                     ⎠
>>> htm2eul(H, deg=True)
(40.8933946491309, 69.2951889453646, -67.7923457014035)
moro.transformations.htmrot(theta, axis='z', deg=False)[source]

Return a homogeneous transformation matrix that represents a rotation “theta” about “axis”.

Parameters
thetafloat, int or symbolic

Rotation angle (given in radians by default)

axisstr

Rotation axis

degbool

¿Is theta given in degrees?

Returns
Hsympy.matrices.dense.MutableDenseMatrix

Homogeneous transformation matrix

Examples

>>> htmrot(pi/2)
⎡0  -1  0  0⎤
⎢           ⎥
⎢1  0   0  0⎥
⎢           ⎥
⎢0  0   1  0⎥
⎢           ⎥
⎣0  0   0  1⎦
>>> htmrot(pi/2, "x")
⎡1  0  0   0⎤
⎢           ⎥
⎢0  0  -1  0⎥
⎢           ⎥
⎢0  1  0   0⎥
⎢           ⎥
⎣0  0  0   1⎦
>>> htmrot(30, "y", True)
⎡0.866025403784439  0         0.5         0⎤
⎢                                          ⎥
⎢        0          1          0          0⎥
⎢                                          ⎥
⎢      -0.5         0  0.866025403784439  0⎥
⎢                                          ⎥
⎣        0          0          0          1⎦
>>> t = symbols("t")
>>> htmrot(t, "x")
⎡1    0        0     0⎤
⎢                     ⎥
⎢0  cos(t)  -sin(t)  0⎥
⎢                     ⎥
⎢0  sin(t)  cos(t)   0⎥
⎢                     ⎥
⎣0    0        0     1⎦
moro.transformations.htmtra(*args, **kwargs)[source]

Calculate the homogeneous transformation matrix of a translation

Parameters
*argslist, tuple, int, float

Translation vector or components

**kwargsfloat, int

dx, dy and dz keyword arguments

Returns
Hsympy.matrices.dense.MutableDenseMatrix

Homogeneous transformation matrix

Examples

>>> htmtra([50,-100,30])
⎡1  0  0   50 ⎤
⎢             ⎥
⎢0  1  0  -100⎥
⎢             ⎥
⎢0  0  1   30 ⎥
⎢             ⎥
⎣0  0  0   1  ⎦
>>> a,b,c = symbols("a,b,c")
>>> htmtra([a,b,c])
⎡1  0  0  a⎤
⎢          ⎥
⎢0  1  0  b⎥
⎢          ⎥
⎢0  0  1  c⎥
⎢          ⎥
⎣0  0  0  1⎦

Using float/integer arguments:

>>> htmtra(10,-40,50)
⎡1  0  0  10 ⎤
⎢            ⎥
⎢0  1  0  -40⎥
⎢            ⎥
⎢0  0  1  50 ⎥
⎢            ⎥
⎣0  0  0   1 ⎦

Using keyword arguments:

>>> htmtra(dz=100,dx=300,dy=-200)
⎡1  0  0  300 ⎤
⎢             ⎥
⎢0  1  0  -200⎥
⎢             ⎥
⎢0  0  1  100 ⎥
⎢             ⎥
⎣0  0  0   1  ⎦
moro.transformations.rot(theta, axis='z', deg=False)[source]
moro.transformations.rot2axa(R, deg=False)[source]

Given a SO(3) matrix return the axis-angle representation.

moro.transformations.rot2eul(R, seq='zxz', deg=False)[source]
moro.transformations.rotx(theta, deg=False)[source]

Calculates the rotation matrix about the x-axis

Parameters
:param theta: Rotation angle (given in radians by default)
:type theta: float, int or `symbolic`
:param deg: ¿Is theta given in degrees?, False is default value.
:type deg: bool
Returns
return

sympy.matrices.dense.MutableDenseMatrix ..

rtype

Rotation matrix (SO3) ..

Examples

>>> rotx(pi)
⎡1  0   0 ⎤
⎢         ⎥
⎢0  -1  0 ⎥
⎢         ⎥
⎣0  0   -1⎦
>>> rotx(60, deg=True)
⎡1          0                  0         ⎤
⎢                                        ⎥
⎢0         0.5         -0.866025403784439⎥
⎢                                        ⎥
⎣0  0.866025403784439         0.5        ⎦
moro.transformations.roty(theta, deg=False)[source]

Calculates the rotation matrix about the y-axis

Parameters
:param theta: Rotation angle (given in radians by default)
:type theta: float, int or `symbolic`
:param deg: ¿Is theta given in degrees?, False is default value.
:type deg: bool
Returns
return

sympy.matrices.dense.MutableDenseMatrix ..

rtype

Rotation matrix (SO3) ..

Examples

>>> roty(pi/3)
⎡         √3 ⎤
⎢1/2   0  ── ⎥
⎢         2  ⎥
⎢            ⎥
⎢ 0    1   0 ⎥
⎢            ⎥
⎢-√3         ⎥
⎢────  0  1/2⎥
⎣ 2          ⎦
>>> roty(30, deg=True)
⎡0.866025403784439  0         0.5       ⎤
⎢                                       ⎥
⎢        0          1          0        ⎥
⎢                                       ⎥
⎣      -0.5         0  0.866025403784439⎦
moro.transformations.rotz(theta, deg=False)[source]

Calculates the rotation matrix about the z-axis

Parameters
:param theta: Rotation angle (given in radians by default)
:type theta: float, int or `symbolic`
:param deg: ¿Is theta given in degrees?, False is default value.
:type deg: bool
Returns
return

sympy.matrices.dense.MutableDenseMatrix ..

rtype

Rotation matrix (SO3) ..

Examples

Using angle in radians,

>>> rotz(pi/2)
⎡0  -1  0⎤
⎢        ⎥
⎢1  0   0⎥
⎢        ⎥
⎣0  0   1⎦

Or symbolic variables,

>>> x = symbols("x")
>>> rotz(x)
⎡cos(x)  -sin(x)  0⎤
⎢                  ⎥
⎢sin(x)  cos(x)   0⎥
⎢                  ⎥
⎣  0        0     1⎦

Using angles in degrees:

>>> rotz(45, deg=True)
⎡0.707106781186548  -0.707106781186547  0⎤
⎢                                        ⎥
⎢0.707106781186547  0.707106781186548   0⎥
⎢                                        ⎥
⎣        0                  0           1⎦
moro.transformations.skew(u)[source]

Return skew-symmetric matrix associated to u vector