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

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_i(i)

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

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

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.

get_dynamic_model()

Returns the dynamic model of the robot

get_kinetic_energy()

Returns the kinetic energy of the robot

get_potential_energy()

Returns the potential energy of the robot

kin_i(i)

Returns the kinetic energy of i-th link

p(i)

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

plot_diagram(num_vals)

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

pot_i(i)

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

qi(i)

Get the i-th articular variable.

rcm_i(i)

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

set_cm_locations(cmlocs)

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.

vcm_i(i)

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

w_i(i)

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

w_ijj(i)

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

z(i)

Get the z_i axis direction w.r.t.

Jv_cm_i

Jw_cm_i

christoffel_symbols

get_coriolis_matrix

get_dynamic_model_matrix_form

get_gravity_torque_vector

get_inertia_matrix

m_i

solve_inverse_kinematics

I_i(i)[source]

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

Parameters
i: int

Link number.

Returns
sympy.matrices.dense.MutableDenseMatrix

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

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

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]
Jw_cm_i(i)[source]
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

T_i^j

christoffel_symbols(i, j, k)[source]
property dof

Get the degrees of freedom of the robot.

Returns
int

Degrees of freedom of the robot

get_coriolis_matrix()[source]
get_dynamic_model()[source]

Returns the dynamic model of the robot

get_dynamic_model_matrix_form()[source]
get_gravity_torque_vector()[source]
get_inertia_matrix()[source]
get_kinetic_energy()[source]

Returns the kinetic energy of the robot

get_potential_energy()[source]

Returns the potential energy of the robot

property joint_limits
kin_i(i)[source]

Returns the kinetic energy of i-th link

m_i(i)[source]
p(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.

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(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
qi(i)[source]

Get the i-th articular variable.

property qis_range
rcm_i(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

set_cm_locations(cmlocs)[source]

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

Parameters
cmlocs: 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.

Parameters
G: list, tuple

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

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 products of inertia are zero.

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)[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]
vcm_i(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(i)[source]

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

Parameters
i: int

Link number.

Returns
sympy.matrices.dense.MutableDenseMatrix

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

Examples

>>> RR = Robot((l1,0,0,q1,"r"), (l2,0,0,q2,"r"))
>>> pprint(RR.w_i(1))
⎡    0    ⎤
⎢         ⎥
⎢    0    ⎥
⎢         ⎥
⎢d        ⎥
⎢──(q₁(t))⎥
⎣dt       ⎦
>>> pprint(RR.w_i(2))
⎡          0          ⎤
⎢                     ⎥
⎢          0          ⎥
⎢                     ⎥
⎢d           d        ⎥
⎢──(q₁(t)) + ──(q₂(t))⎥
⎣dt          dt       ⎦
w_ijj(i)[source]

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

Since we are using Denavit-Hartenberg frames, then:

\[\begin{split}\omega_{{i-i,i}}^{{i-1}} = \begin{bmatrix} 0 \\ 0 \\ \dot{{q}}_i \end{bmatrix}\end{split}\]

If the i-th joint is revolute, or:

\[\begin{split}\omega_{{i-i,i}}^{{i-1}} = \begin{bmatrix} 0 \\ 0 \\ 0 \end{bmatrix}\end{split}\]

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