The transformations module
Numython R&D, (c) 2026 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.
- Parameters:
- ksympy.matrices.dense.MutableDenseMatrix or list or tuple
Axis of rotation, must be a 3D vector. If k is given as a list or tuple, it will be converted to a sympy Matrix.
- thetafloat, int or symbolic
Rotation angle (given in radians by default).
- Returns:
- Rsympy.matrices.dense.MutableDenseMatrix
Rotation matrix in SO(3) corresponding to a rotation of “theta” about the axis defined by “k”.
- moro.transformations.dh(a, alpha, d, theta)[source]
Compute the Denavit-Hartenberg homogeneous transformation matrix.
- Parameters:
- aint, float or symbolic
Link length (DH parameter).
- alphaint, float or symbolic
Link twist (DH parameter).
- dint, float or symbolic
Link offset (DH parameter).
- thetaint, float or symbolic
Joint angle (DH parameter).
- Returns:
- sympy.matrices.dense.MutableDenseMatrix
Denavit-Hartenberg homogeneous transformation matrix of shape (4, 4).
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.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:
- H
sympy.matrices.dense.MutableDenseMatrix Homogeneous transformation matrix
- H
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:
- H
sympy.matrices.dense.MutableDenseMatrix Homogeneous transformation matrix
- H
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]
Return a rotation matrix that represents a rotation of “theta” about “axis”.
- Parameters:
- thetafloat, int or symbolic
Rotation angle (given in radians by default)
- axisstr
Rotation axis, “x”, “y” or “z” (default is “z”)
- degbool
¿Is theta given in degrees?, False is default value.
- moro.transformations.rot2axa(R, deg=False)[source]
Given a SO(3) matrix return the axis-angle representation.
- Parameters:
- Rsympy.matrices.dense.MutableDenseMatrix
Rotation matrix in SO(3).
- degbool
If True, the angle is returned in degrees. By default, it is False (angle in radians or symbolic).
- Returns:
- ksympy.matrices.dense.MutableDenseMatrix
Axis of rotation, a 3D vector.
- thetafloat, int or symbolic
Rotation angle (given in radians by default, or symbolic).
- moro.transformations.rotx(theta, deg=False)[source]
Calculates the rotation matrix about the x-axis
- Parameters:
- thetafloat, int or symbolic
Rotation angle (given in radians by default)
- degbool
¿Is theta given in degrees?, False is default value.
- Returns:
- sympy.matrices.dense.MutableDenseMatrix
Rotation matrix in SO(3).
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:
- thetafloat, int or symbolic
Rotation angle (given in radians by default)
- degbool
¿Is theta given in degrees?, False is default value.
- Returns:
- sympy.matrices.dense.MutableDenseMatrix
Rotation matrix in SO(3).
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]
Calculate the rotation matrix about the z-axis.
- Parameters:
- thetafloat, int or symbolic
Rotation angle. By default, the value is assumed to be given in radians.
- degbool, optional
If True, theta is interpreted as degrees. Default is False.
- Returns:
- sympy.matrices.dense.MutableDenseMatrix
Rotation matrix in SO(3).
Examples
Using angle in radians:
>>> rotz(pi/2) ⎡0 -1 0⎤ ⎢ ⎥ ⎢1 0 0⎥ ⎢ ⎥ ⎣0 0 1⎦
Using 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.
- Parameters:
- usympy.matrices.dense.MutableDenseMatrix or list or tuple
A 3D vector. If u is given as a list or tuple, it will be converted to a sympy Matrix.
- Returns:
- Ssympy.matrices.dense.MutableDenseMatrix
Skew-symmetric matrix associated to u.