Dynamics of Serial Robotic Manipulators

3 minute read

Published:

In this post, we’ll cover the essential knowledge needed to compute the dynamics of a general rigid serial robotic manipulator. We’ll use the Euler-Lagrange equations to derive the dynamics of the manipulator.

This post assumes the reader’s knowledge about Lagrangian Mechanics, Euler-Lagrange equations.

Newton-Formulation v/s Lagrangian Formulation

  • Newton analysis requires the second-order properties of motion, i.e linear and angular accelerations of each link, whereas Lagrangian approach requires information about motion only upto first order.
  • The internal, reactive forces needs to be eliminated to arrive at the newtonian equation of motions, whereas Lagrangian approach safely ignores the play of these forces in the formulation.

Euler-Lagrange Equation

Lagrangian formulation needs information on

  • $T(q, \dot{q}, t)$ - Kinetic energy of the system.
  • $V(q, \dot{q}, t)$ - Potential energy of the system.

where q denotes a n-vector of generalized coordinates, where n is the degrees of freedom of the system, t denotes time. The generalized coordinates describe the mechanical system completely without introducing any holonomic constraints.

We then define the functional, namely Lagrangian of the system

\[\begin{equation} L = T - V \end{equation}\]

The equation of motion of the system is given by

\(\begin{equation} \frac{d}{dt}(\frac{\partial{L}}{\partial{\dot{q}}}) - \frac{\partial{L}}{\partial{q}} = Q^{nc} \label{eq:lagrange} \end{equation}\) where $Q^{nc}$ denotes the vector of non-conservative generalized forces.

General Form of the Lagrangian Equation

Let us consider the following

\(\begin{equation} T(q, \dot{q}, t) = \frac{1}{2} \dot{q}^{T} M(q) \dot{q} \end{equation}\) \(\begin{equation} \frac{\partial{L}}{\partial{\dot{q}}} = \frac{\partial{T}}{\partial{\dot{q}}} = \frac{1}{2} (M+M^{T}) \dot{q} = M\dot{q} \end{equation}\)

where M is the mass matrix, which is symmetric. The entity $M\dot{q}$ is known as the generalized momentum. Proceeding,

\[\begin{equation} \frac{d}{dt}(\frac{\partial{L}}{\partial{\dot{q}}}) = M\ddot{q} + \dot{M}\dot{q} \end{equation}\]

Similarly,

\[\begin{equation} \frac{\partial{L}}{\partial{q}} = \frac{\partial{T}}{\partial{q}}-\frac{\partial{V}}{\partial{q}} = \frac{1}{2}\dot{q}^{T}\frac{\partial{M}}{\partial{q}}\dot{q}-\frac{\partial{V}}{\partial{q}} \end{equation}\]

After substituting in \eqref{eq:lagrange} and rearranging,

\[\begin{equation} M\ddot{q}+(\dot{M}-\frac{1}{2}\dot{q}^{T}\frac{\partial{M}}{\partial{q}})\dot{q}+\frac{\partial{V}}{\partial{q}} = Q^{nc} \end{equation}\]

Which can be formally written as

\[\begin{equation} \boxed{M(q)\dot{q}+C(q, \dot{q})\dot{q}+G(q) = Q^{nc}(q,\dot{q},t)} \end{equation}\]

The Lagrangian Dynamics can be written as \(\begin{equation} M(q)\dot{q}+C(q, \dot{q})\dot{q}+G(q) = Q^{nc}(q,\dot{q},t) \end{equation}\) where

  • $C(q, \dot{q}) = (\dot{M}-\frac{1}{2}\dot{q}^{T}\frac{\partial{M}}{\partial{q}})$ is known as the Coriolis and the Centripetal term
  • $G(q) = \frac{\partial{V}}{\partial{q}}$ is known as the Gravitational or Potential term
  • $M(q)$ is symmetric and positive definite (T is positive)
  • $C(q, \dot{q})$ can be derived from $M(q)$ alone using the formula \(\begin{equation} C_{ij} = \frac{1}{2}\sum_{k=1}^n(\frac{\partial{M_{ij}}}{\partial{q_{k}}} + \frac{\partial{M_{ik}}}{\partial{q_{j}}} - \frac{\partial{M_{kj}}}{\partial{q_{i}}})\dot{q_{k}} \label{eq:cmat} \end{equation}\)

Computation of Mass Matrix

To derive the mass matrix, let’s write down the kinetic energy T in terms on $m_{i}$ (mass of ith link), $I_{c}$ (inertia matrix in body-fixed frame) located at mass center $p_{c_{i}}$, $v_{p_{c_{i}}}$ (linear velocity of the mass center), $\omega_{i}$(angular velocity of the link in body-fixed frame)

The kinetic energy of the ith link is

\[\begin{equation} T_{i} = \frac{1}{2}v_{p{c{i}}}^{T}m_{i}v_{p{c{i}}}+\frac{1}{2}\omega_{i}^{T}I_{c_{i}}\omega_{i} \label{eq:tmat} \end{equation}\]

From velocity analysis, we can write \(\begin{equation} v_{p_{c_{i}}} = \frac{dp_{c_{i}}}{dt} = J_{v_{p_{c_{i}}}}\dot{q} \label{eq:linjac} \end{equation}\) \(\begin{equation} \omega_{i} = J_{\omega_{c_{i}}}\dot{q} \label{eq:angjac} \end{equation}\)

where, Linear Velocity Jacobian \(\begin{equation} J_{v_{p_{c_{i}}}} = \frac{\partial{p_{c_{i}}}}{\partial{q}} \end{equation}\) and, body-fixed Angular Velocity Jacobian \(\begin{equation} J_{\omega_{c_{i}}} = R^{T}\dot{R} \end{equation}\)

Substituting \eqref{eq:linjac}, \eqref{eq:angjac} in \eqref{eq:tmat}

\(\begin{equation} T_{i} = \frac{1}{2}\dot{q}^{T}J_{v_{p_{c_{i}}}}^{T}m_{i}J_{v_{p_{c_{i}}}}\dot{q}+\frac{1}{2}\dot{q}^{T}J_{\omega_{c_{i}}}^{T}I_{c_{i}}J_{\omega_{c_{i}}}\dot{q} \end{equation}\) \(\begin{equation} T_{i} = \frac{1}{2}\dot{q}^{T}(m_{i}J_{v_{p_{c_{i}}}}^{T}J_{v_{p_{c_{i}}}}+J_{\omega_{c_{i}}}^{T}I_{c_{i}}J_{\omega_{c_{i}}})\dot{q} \end{equation}\) \(\begin{equation} M_{i} = m_{i}J_{v_{p_{c_{i}}}}^{T}J_{v_{p_{c_{i}}}}+J_{\omega_{c_{i}}}^{T}I_{c_{i}}J_{\omega_{c_{i}}} \end{equation}\) denotes the mass matrix of the ith link. Since the total kinetic energy of the system is just the sum of each link’s kinetic energy, then the total mass matrix is the sum of each link’s mass matrix

The Mass matrix is computed by calculating the individual link’s mass and then adding up contributions from all links \(\begin{equation} M_{i} = m_{i}J_{v_{p_{c_{i}}}}^{T}J_{v_{p_{c_{i}}}}+J_{\omega_{c_{i}}}^{T}I_{c_{i}}J_{\omega_{c_{i}}} \end{equation}\) \(\begin{equation} M = M_{1} + M_{2} + ... + M_{n} \label{eq:mass} \end{equation}\)

Steps to Derive the equation of motion

  1. Construct $M(q)$ using \eqref{eq:mass}
  2. Compute $C(q, \dot{q})$ from $M(q)$ using \eqref{eq:cmat}
  3. Calculate $V$ and differential with $q$ to get $G$

Leave a Comment