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

class moro.core.RigidBody2D(points)[source]

Bases: object

Defines a rigid body (two-dimensional) through a series of points that make it up.

Parameters:
points: list, tuple

A list of 2-lists (or list of 2-tuples) containing the N-points that make up the rigid body.

Examples

>>> points = [(0,0), (1,0), (0,1)]
>>> rb = RigidBody2D(points)
Attributes:
H
points

Methods

draw([color, kaxis])

Draw the rigid body

get_centroid()

Return the centroid of the rigid body

move(q)

Moves the rigid body

restart()

Restart to initial coordinates of the rigid body

rotate(angle)

Rotates the rigid body around z-axis.

property H
draw(color='r', kaxis=None)[source]

Draw the rigid body

get_centroid()[source]

Return the centroid of the rigid body

move(q)[source]

Moves the rigid body

property points
restart()[source]

Restart to initial coordinates of the rigid body

rotate(angle)[source]

Rotates the rigid body around z-axis.

class moro.core.Robot(*args)[source]

Bases: object

Define a robot-serial-arm given the Denavit-Hartenberg parameters and the joint type, as tuples (or lists). Each tuple must have the form:

(a_i, alpha_i, d_i, theta_i)

Or including the joint type:

(a_i, alpha_i, d_i, theta_i, joint_type)

All parameters are int or floats, or a symbolic variable of SymPy. Numeric angles must be passed in radians. If joint_type is not passed, the joint is assumed to be revolute.

Examples

>>> rr = Robot((l1,0,0,q1), (l2,0,0,q2))

or

>>> rr2 = Robot((l1,0,0,q1,"r"), (l2,0,0,q2,"r"))
Attributes:
J

Get the geometric jacobian matrix of the end-effector.

T

Get the homogeneous transformation matrix of {n}-Frame (end-effector) w.r.t.

dof

Get the degrees of freedom of the robot.

joint_limits
qis_range

Methods

I_cm(i)

Return the inertia tensor of i-th link w.r.t.

I_cm0(i)

Return the inertia tensor of [i-th] link w.r.t.

J_cm_i(i)

Compute the jacobian matrix of the center of mass of the i-th link.

J_point(point, i)

Compute the jacobian matrix of a specific point in the manipulator.

Jv_cm_i(i)

Return the linear velocity Jacobian matrix of the center of mass of the i-th link.

Jw_cm_i(i)

Return the angular velocity Jacobian matrix of the center of mass of the i-th link.

R_i0(i)

Get the rotation matrix of {i}-Frame w.r.t.

T_i0(i)

Get the homogeneous transformation matrix of {i}-Frame w.r.t.

T_ij(i, j)

Get the homogeneous transformation matrix of {i}-Frame w.r.t.

christoffel_symbols(i, j, k, M)

Return the Christoffel symbol of the first kind:

get_coriolis_matrix()

Return the Coriolis matrix C(q,q').

get_dynamic_model()

Returns the dynamic model of the robot using the Euler-Lagrange formulation.

get_dynamic_model_matrix_form()

Return the dynamic model of the robot in matrix form:

get_gravity_torque_vector()

Compute the gravity torque vector G(q).

get_inertia_matrix()

Return the inertia matrix M(q) of the robot.

get_kinetic_energy()

Returns the total kinetic energy of the robot

get_potential_energy()

Returns the total potential energy of the robot:

joint_type(i)

Return the type of the i-th joint.

kin(i)

Returns the kinetic energy of i-th link.

m(i)

Return the mass of the i-th link.

plot_diagram(num_vals)

Draw a simple wire-diagram or kinematic-diagram of the manipulator.

pot(i)

Returns the potential energy of the [i-th] link.

q(i)

Return the i-th joint variable.

q_dot(i)

Return the time derivative of the i-th joint variable.

qi(i)

Get the i-th articular variable.

r_cm(i)

Return the position of the center of mass of the i-th link w.r.t.

r_o(i)

Get the position (of the origin of coordinates) of the {i}-Frame w.r.t.

set_cm_locations(cm_locations)

Set the positions of the center of mass for each link.

set_gravity_vector(G)

Set the gravity vector in the base frame.

set_inertia_tensors([tensors])

Inertia tensor w.r.t.

set_masses([masses])

Set mass for each link using a list like: [m1, m2, ..., mn], where m1, m2, ..., mn, are numeric or symbolic values.

v_cm(i)

Return the velocity of the center of mass of the i-th link w.r.t.

w(i)

Compute the angular velocity of the [i]-link w.r.t.

w_rel0(i)

Return the angular velocity of the [i]-link w.r.t.

z(i)

Get the z_i axis direction w.r.t.

solve_inverse_kinematics

I_cm(i)[source]

Return the inertia tensor of i-th link w.r.t. {i}’ frame (located in the center of mass of link [i] and aligned with the {i}-Frame).

Parameters:
i: int

Link number.

Returns:
sympy.matrices.dense.MutableDenseMatrix

Inertia tensor of the [i]-link w.r.t. {i}’-Frame.

I_cm0(i)[source]

Return the inertia tensor of [i-th] link w.r.t. a frame located in the center of mass of link [i] and aligned with the base frame.

Parameters:
i: int

Link number.

Returns:
sympy.matrices.dense.MutableDenseMatrix

Inertia tensor of the [i]-link w.r.t. {0}-Frame.

property J

Get the geometric jacobian matrix of the end-effector.

Returns:
sympy.matrices.dense.MutableDenseMatrix

Get the geometric jacobian matrix of the end-effector.

J_cm_i(i)[source]

Compute the jacobian matrix of the center of mass of the i-th link.

Parameters:
iint

Link number.

Returns:
sympy.matrices.dense.MutableDenseMatrix

Jacobian matrix of i-th CoM.

J_point(point, i)[source]

Compute the jacobian matrix of a specific point in the manipulator.

Parameters:
pointlist

Coordinates of the point w.r.t. {i}-Frame.

iint

Link number in which the point is located.

Returns:
sympy.matrices.dense.MutableDenseMatrix

Jacobian matrix of the point.

Jv_cm_i(i)[source]

Return the linear velocity Jacobian matrix of the center of mass of the i-th link.

Parameters:
iint

Link number.

Jw_cm_i(i)[source]

Return the angular velocity Jacobian matrix of the center of mass of the i-th link.

Parameters:
iint

Link number.

R_i0(i)[source]

Get the rotation matrix of {i}-Frame w.r.t. {0}-Frame.

Returns:
sympy.matrices.dense.MutableDenseMatrix

Returns \(R_i^0\)

property T

Get the homogeneous transformation matrix of {n}-Frame (end-effector) w.r.t. {0}-Frame.

Returns:
sympy.matrices.dense.MutableDenseMatrix

\(T_n^0\)

T_i0(i)[source]

Get the homogeneous transformation matrix of {i}-Frame w.r.t. {0}-Frame.

Returns:
sympy.matrices.dense.MutableDenseMatrix

Returns \(T_i^0\)

T_ij(i, j)[source]

Get the homogeneous transformation matrix of {i}-Frame w.r.t. {j}-Frame.

Returns:
sympy.matrices.dense.MutableDenseMatrix

Returns \(T_i^j\)

christoffel_symbols(i, j, k, M)[source]

Return the Christoffel symbol of the first kind:

\[c_{{i,j,k}} = \frac{1}{2} \left( \frac{{\partial M_{{i,j}}}}{{\partial q_k}} + \frac{{\partial M_{{i,k}}}}{{\partial q_j}} - \frac{{\partial M_{{j,k}}}}{{\partial q_i}} \right)\]
property dof

Get the degrees of freedom of the robot.

Returns:
int

Degrees of freedom of the robot

get_coriolis_matrix()[source]

Return the Coriolis matrix C(q,q’). The Coriolis matrix is computed using the Christoffel symbols of the first kind:

\[C_{{i,j}} = \sum_{{k=1}}^n c_{{i,j,k}} \dot{{q}}_k\]
get_dynamic_model()[source]

Returns the dynamic model of the robot using the Euler-Lagrange formulation. The returned value is a list of equations, one for each joint, of the form:

\[\frac{d}{dt} \left( \frac{\partial L}{\partial \dot{{q}}_i} \right) - \frac{\partial L}{\partial q_i} = \tau_i\]

where \(L\) is the Lagrangian of the system, defined as \(\mathbb{L} = K - P\), where K is the kinetic energy and P is the potential energy.

get_dynamic_model_matrix_form()[source]

Return the dynamic model of the robot in matrix form:

\[M(q) \ddot{{q}} + C(q,\dot{{q}}) \dot{{q}} + G(q) = \tau\]

where \(M(q)\) is the inertia matrix, \(C(q,q')\) is the Coriolis matrix, \(G(q)\) is the gravity torque vector, and \(\tau\) is the vector of joint torques.

get_gravity_torque_vector()[source]

Compute the gravity torque vector G(q). The gravity torque vector is computed as the gradient of the potential energy of the system:

\[G(q) = \nabla U(q) = \left[ \frac{{\partial U}}{{\partial q_1}}, \frac{{\partial U}}{{\partial q_2}}, ..., \frac{{\partial U}}{{\partial q_n}} \right]^T\]
Returns:
sympy.matrices.dense.MutableDenseMatrix

Gravity torque vector G(q)

get_inertia_matrix()[source]

Return the inertia matrix M(q) of the robot. The inertia matrix is computed as:

\[M(q) = \sum_{{i=1}}^n m_i J_{v_i}^T J_{v_i} + J_{w_i}^T R_i I_i R_i^T J_{w_i}\]

where \(m_i\) is the mass of the i-th link, \(J_{v_i}\) is the linear velocity Jacobian matrix of the center of mass of the i-th link, \(J_{w_i}\) is the angular velocity Jacobian matrix of the center of mass of the i-th link, \(R_i\) is the rotation matrix of the i-th link w.r.t. the base frame, and \(I_i\) is the inertia tensor of the i-th link w.r.t. a frame located in its center of mass and aligned with the {i}-Frame.

Returns:
sympy.matrices.dense.MutableDenseMatrix

Inertia matrix M(q)

get_kinetic_energy()[source]

Returns the total kinetic energy of the robot

get_potential_energy()[source]

Returns the total potential energy of the robot:

\[P(q) = \sum_{{i=1}}^n P_i = - \sum_{{i=1}}^n m_i \mathbf{g}^T \mathbf{r}_{G_i}\]
property joint_limits
joint_type(i)[source]

Return the type of the i-th joint. “r” for revolute, “p” for prismatic.

Parameters:
iint

Joint number.

kin(i)[source]

Returns the kinetic energy of i-th link.

\[K_i = \frac{1}{2} m_i \mathbf{v}_{G_i}^T \mathbf{v}_{G_i} + \frac{1}{2} \boldsymbol{\omega}_i^T I_i \boldsymbol{\omega}_i\]
Parameters:
i: int

Link number.

m(i)[source]

Return the mass of the i-th link.

Parameters:
i: int

Link number.

plot_diagram(num_vals)[source]

Draw a simple wire-diagram or kinematic-diagram of the manipulator.

Parameters:
num_valsdict

Dictionary like: {svar1: nvalue1, svar2: nvalue2, …}, where svar1, svar2, … are symbolic variables that are currently used in model, and nvalue1, nvalue2, … are the numerical values that will substitute these variables.

pot(i)[source]

Returns the potential energy of the [i-th] link.

\[P_i = - m_i \mathbf{g}^T \mathbf{r}_{G_i} \]
Parameters:
i: int

Link number.

Returns:
q(i)[source]

Return the i-th joint variable.

Parameters:
iint

Joint number.

q_dot(i)[source]

Return the time derivative of the i-th joint variable.

Parameters:
iint

Joint number.

qi(i)[source]

Get the i-th articular variable.

Parameters:
i: int

Joint number (starting from 1)

property qis_range
r_cm(i)[source]

Return the position of the center of mass of the i-th link w.r.t. the base frame.

Parameters:
i: int

Link number

Returns:
sympy.matrices.dense.MutableDenseMatrix

A column vector

r_o(i)[source]

Get the position (of the origin of coordinates) of the {i}-Frame w.r.t. {0}-Frame

Parameters:
i: int

{i}-th Frame

Returns:
sympy.matrices.dense.MutableDenseMatrix

The position of {i}-Frame as a 3-component vector.

set_cm_locations(cm_locations)[source]

Set the positions of the center of mass for each link. The position of the center of mass of the i-th link must be defined as a list or tuple of three elements that correspond to the x, y, z coordinates of the center of mass w.r.t. {i}-Frame.

Parameters:
cm_locations: list, tuple

A list of lists (or tuples) or a tuple of tuples (or lists) containing each center of mass position w.r.t. its reference frame.

Examples

>>> RR = Robot((l1,0,0,q1,"r"), (l2,0,0,q2,"r"))
>>> RR.set_cm_locations([(-lc1,0,0), (-lc2,0,0)])
set_gravity_vector(G)[source]

Set the gravity vector in the base frame. The gravity vector must be defined as a list or tuple of three elements that correspond to the x, y, z components of the gravity vector in the base frame.

Parameters:
G: list, tuple

A list or tuple of three elements that define the gravity vector in the base frame.

Examples

>>> RR = Robot((l1,0,0,q1,"r"), (l2,0,0,q2,"r"))
>>> RR.set_gravity_vector((0,-g,0))
set_inertia_tensors(tensors=None)[source]

Inertia tensor w.r.t. {i}’-Frame. Consider that the reference frame {i}’ is located at the center of mass of link [i] and oriented in the same way as {i}-Frame. By default (if tensors argument is not passed), it is assumed that each link is symmetrical to, at least, two planes of the reference frame located in its center of mass, then the inertia tensor of each link is defined as a diagonal matrix with the moments of inertia as diagonal elements, and the products of inertia as zero. The moments of inertia are defined as symbolic variables of the form: I_{x_ix_i}, I_{y_iy_i}, I_{z_iz_i}, where i is the link number.

Parameters:
tensors: sympy.matrices.dense.MutableDenseMatrix

A list containinig sympy.matrices.dense.MutableDenseMatrix that corresponds to each inertia tensor w.r.t. {i}’-Frame.

set_masses(masses=None)[source]

Set mass for each link using a list like: [m1, m2, …, mn], where m1, m2, …, mn, are numeric or symbolic values.

Parameters:
masses: list, tuple

A list of numerical or symbolic values that correspond to link masses.

solve_inverse_kinematics(pose, q0=None)[source]
v_cm(i)[source]

Return the velocity of the center of mass of the i-th link w.r.t. the base frame.

Parameters:
i: int

Link number

Returns:
sympy.matrices.dense.MutableDenseMatrix

A column vector

w(i)[source]

Compute the angular velocity of the [i]-link w.r.t. base {0}-Frame. The angular velocity of the [i]-link w.r.t. base {0}-Frame can be computed as the sum of the relative angular velocities of each link w.r.t. its previous link, described in the base frame:

\[\boldsymbol{\omega}_i = \sum_{{k=1}}^i \boldsymbol{\omega}_{{k-1,k}}\]
Parameters:
i: int

Link number.

Returns:
sympy.matrices.dense.MutableDenseMatrix

Angular velocity of the [i]-link w.r.t. {0}-Frame.

w_rel0(i)[source]

Return the angular velocity of the [i]-link w.r.t. [i-1]-link, described in {0}-Frame.

Since we are using Denavit-Hartenberg frames, then:

\[\omega_{{i-i,i}} = \dot{{q}}_i \mathbf{z}_{i-1}\]

If the i-th joint is revolute, or:

\[\omega_{{i-i,i}} = \mathbf{0}\]

If the i-th joint is a prismatic.

Parameters:
iint

Link number.

z(i)[source]

Get the z_i axis direction w.r.t. {0}-Frame.

Parameters:
i: int

{i}-th Frame

Returns:
sympy.matrices.dense.MutableDenseMatrix

The direction of z_i axis