Skip to content

Robot Dynamics

Overview

Dynamics studies the relationship between forces/torques and motion. Unlike kinematics, which concerns only geometric relationships, dynamics must account for physical quantities such as mass, inertia, and gravity. Dynamics is the foundation of robot control.

Dynamics has two core problems:

Problem Input Output Application
Forward Dynamics Joint torques \(\tau\) Joint accelerations \(\ddot{q}\) Simulation
Inverse Dynamics Desired trajectory \(q, \dot{q}, \ddot{q}\) Required torques \(\tau\) Control

1 Standard Form of the Equations of Motion

The robot's equations of motion can be written in the unified form:

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

Meaning of each term:

Symbol Name Dimension Physical Meaning
\(M(q)\) Mass/Inertia Matrix \(n \times n\) Positive definite symmetric, characterizes inertia
\(C(q, \dot{q})\dot{q}\) Coriolis and Centrifugal Forces \(n \times 1\) Velocity coupling effects
\(g(q)\) Gravity Term \(n \times 1\) Projection of gravity in joint space
\(\tau\) Joint Torques/Forces \(n \times 1\) Actuator output

Important Properties

  • \(M(q)\) is symmetric positive definite: \(M = M^T\), \(x^T M x > 0, \; \forall x \neq 0\)
  • \(\dot{M} - 2C\) is skew-symmetric (when \(C\) is defined using Christoffel symbols)
  • This property is crucial for adaptive control and passivity analysis

2 Newton-Euler Recursive Method

The Newton-Euler method is the most efficient approach for computing inverse dynamics, with computational complexity \(O(n)\).

2.1 Algorithm Flow

graph TB
    subgraph "Forward Recursion: Base to End-Effector"
        A["Link 1"] -->|"ω₁, α₁, a₁"| B["Link 2"]
        B -->|"ω₂, α₂, a₂"| C["Link 3"]
        C -->|"..."| D["Link n"]
    end
    subgraph "Backward Recursion: End-Effector to Base"
        D -->|"f_n, τ_n"| C
        C -->|"f₂, τ₂"| B
        B -->|"f₁, τ₁"| A
    end
    style A fill:#e8f4fd,stroke:#2196F3
    style D fill:#fff3e0,stroke:#FF9800

2.2 Forward Recursion (Velocity and Acceleration Propagation)

Starting from the base (\(i=0\)), compute the angular velocity, angular acceleration, and linear acceleration of each link sequentially toward the end-effector (\(i=n\)).

Revolute Joint \(i\):

Angular velocity propagation:

\[ \omega_i = \;^{i}R_{i-1} \, \omega_{i-1} + \dot{\theta}_i \, \hat{z}_i \]

Angular acceleration propagation:

\[ \dot{\omega}_i = \;^{i}R_{i-1} \, \dot{\omega}_{i-1} + \;^{i}R_{i-1} \, \omega_{i-1} \times \dot{\theta}_i \hat{z}_i + \ddot{\theta}_i \hat{z}_i \]

Link origin linear acceleration:

\[ \dot{v}_i = \;^{i}R_{i-1} [\dot{\omega}_{i-1} \times p_{i-1,i} + \omega_{i-1} \times (\omega_{i-1} \times p_{i-1,i}) + \dot{v}_{i-1}] \]

Center of mass linear acceleration:

\[ \dot{v}_{c_i} = \dot{\omega}_i \times s_i + \omega_i \times (\omega_i \times s_i) + \dot{v}_i \]

where \(s_i\) is the vector from the link frame origin to the center of mass.

2.3 Backward Recursion (Force and Torque Propagation)

Starting from the end-effector (\(i=n\)), compute the forces and torques at each joint sequentially toward the base (\(i=0\)).

Net force on link \(i\) (Newton's equation):

\[ F_i = m_i \dot{v}_{c_i} \]

Net torque on link \(i\) (Euler's equation):

\[ N_i = I_i \dot{\omega}_i + \omega_i \times (I_i \omega_i) \]

Recursive force and torque toward the base:

\[ f_i = \;^{i}R_{i+1} \, f_{i+1} + F_i \]
\[ n_i = N_i + \;^{i}R_{i+1} \, n_{i+1} + s_i \times F_i + p_{i,i+1} \times (^{i}R_{i+1} \, f_{i+1}) \]

Final joint torque:

\[ \tau_i = n_i^T \hat{z}_i \]

3 Lagrangian Method

3.1 Basic Principle

The Lagrangian method is based on an energy perspective and is more intuitive for modeling, but has computational complexity \(O(n^3)\) or \(O(n^4)\).

Define the Lagrangian function:

\[ L = K - P \]

where \(K\) is the total kinetic energy and \(P\) is the total potential energy.

Euler-Lagrange Equations:

\[ \frac{d}{dt}\frac{\partial L}{\partial \dot{q}_i} - \frac{\partial L}{\partial q_i} = \tau_i, \quad i = 1, 2, \ldots, n \]

3.2 Kinetic and Potential Energy

Kinetic Energy of Link \(i\):

\[ K_i = \frac{1}{2} m_i v_{c_i}^T v_{c_i} + \frac{1}{2} \omega_i^T I_i \omega_i \]

The total kinetic energy can be written as a quadratic form:

\[ K = \frac{1}{2} \dot{q}^T M(q) \dot{q} \]

where \(M(q)\) is the mass matrix with elements:

\[ M_{ij}(q) = \sum_{k=\max(i,j)}^{n} \left[ m_k \left(\frac{\partial v_{c_k}}{\partial \dot{q}_i}\right)^T \frac{\partial v_{c_k}}{\partial \dot{q}_j} + \left(\frac{\partial \omega_k}{\partial \dot{q}_i}\right)^T I_k \frac{\partial \omega_k}{\partial \dot{q}_j} \right] \]

Potential Energy of Link \(i\):

\[ P_i = m_i g^T p_{c_i} \]

Total potential energy:

\[ P = \sum_{i=1}^{n} m_i g^T p_{c_i} \]

3.3 Deriving Each Term of the Equations of Motion

Expanding the Euler-Lagrange equations yields:

\[ \tau_i = \sum_{j=1}^{n} M_{ij}(q) \ddot{q}_j + \sum_{j=1}^{n} \sum_{k=1}^{n} c_{ijk} \dot{q}_j \dot{q}_k + g_i(q) \]

where the Christoffel symbols are:

\[ c_{ijk} = \frac{1}{2} \left( \frac{\partial M_{ij}}{\partial q_k} + \frac{\partial M_{ik}}{\partial q_j} - \frac{\partial M_{jk}}{\partial q_i} \right) \]

4.1 System Description

  • Link 1: mass \(m_1\), length \(l_1\), center of mass at \(l_{c1}\), inertia \(I_1\)
  • Link 2: mass \(m_2\), length \(l_2\), center of mass at \(l_{c2}\), inertia \(I_2\)
  • Gravity along the \(-y\) direction

4.2 Position and Velocity

Link 1 center of mass position:

\[ x_{c1} = l_{c1} \cos\theta_1, \quad y_{c1} = l_{c1} \sin\theta_1 \]

Link 2 center of mass position:

\[ x_{c2} = l_1 \cos\theta_1 + l_{c2} \cos(\theta_1 + \theta_2) \]
\[ y_{c2} = l_1 \sin\theta_1 + l_{c2} \sin(\theta_1 + \theta_2) \]

4.3 Kinetic Energy

\[ K_1 = \frac{1}{2}(m_1 l_{c1}^2 + I_1)\dot{\theta}_1^2 \]
\[ K_2 = \frac{1}{2}m_2\left[l_1^2 \dot{\theta}_1^2 + l_{c2}^2(\dot{\theta}_1 + \dot{\theta}_2)^2 + 2l_1 l_{c2} \cos\theta_2 \, \dot{\theta}_1(\dot{\theta}_1 + \dot{\theta}_2)\right] + \frac{1}{2}I_2(\dot{\theta}_1 + \dot{\theta}_2)^2 \]

4.4 Potential Energy

\[ P = m_1 g l_{c1} \sin\theta_1 + m_2 g [l_1 \sin\theta_1 + l_{c2} \sin(\theta_1 + \theta_2)] \]

4.5 Mass Matrix

\[ M(q) = \begin{bmatrix} m_1 l_{c1}^2 + m_2(l_1^2 + l_{c2}^2 + 2l_1 l_{c2}\cos\theta_2) + I_1 + I_2 & m_2(l_{c2}^2 + l_1 l_{c2}\cos\theta_2) + I_2 \\ m_2(l_{c2}^2 + l_1 l_{c2}\cos\theta_2) + I_2 & m_2 l_{c2}^2 + I_2 \end{bmatrix} \]

4.6 Coriolis and Centrifugal Force Matrix

Let \(h = m_2 l_1 l_{c2} \sin\theta_2\), then:

\[ C(q, \dot{q}) = \begin{bmatrix} -h\dot{\theta}_2 & -h(\dot{\theta}_1 + \dot{\theta}_2) \\ h\dot{\theta}_1 & 0 \end{bmatrix} \]

4.7 Gravity Term

\[ g(q) = \begin{bmatrix} (m_1 l_{c1} + m_2 l_1)g\cos\theta_1 + m_2 l_{c2} g \cos(\theta_1 + \theta_2) \\ m_2 l_{c2} g \cos(\theta_1 + \theta_2) \end{bmatrix} \]

4.8 Complete Equations of Motion

\[ \begin{bmatrix} \tau_1 \\ \tau_2 \end{bmatrix} = M(q)\begin{bmatrix} \ddot{\theta}_1 \\ \ddot{\theta}_2 \end{bmatrix} + C(q, \dot{q})\begin{bmatrix} \dot{\theta}_1 \\ \dot{\theta}_2 \end{bmatrix} + g(q) \]

5 Properties and Applications of Dynamics

5.1 Key Properties

Property 1: \(M(q)\) is Symmetric Positive Definite

This ensures the kinetic energy is always positive and guarantees the existence and uniqueness of solutions to the equations of motion.

Property 2: \(\dot{M} - 2C\) is Skew-Symmetric (under Christoffel definition)

\[ x^T(\dot{M} - 2C)x = 0, \quad \forall x \in \mathbb{R}^n \]

This property implies system passivity, playing a key role in adaptive control.

Property 3: Linear Parameterization

The equations of motion can be written as:

\[ M(q)\ddot{q} + C(q, \dot{q})\dot{q} + g(q) = Y(q, \dot{q}, \ddot{q}) \, \pi \]

where \(Y\) is the regressor matrix and \(\pi\) is the dynamics parameter vector. This property is the foundation of adaptive control.

5.2 Forward Dynamics Solution

Forward dynamics is used for simulation. Given \(\tau\), solve for \(\ddot{q}\):

\[ \ddot{q} = M(q)^{-1} [\tau - C(q, \dot{q})\dot{q} - g(q)] \]

Combined with numerical integration (e.g., Runge-Kutta), robot motion can be simulated.

5.3 Inverse Dynamics Solution

Inverse dynamics is used for control. Given the desired trajectory \(q_d(t)\), compute the feedforward torque:

\[ \tau_{\text{ff}} = M(q_d)\ddot{q}_d + C(q_d, \dot{q}_d)\dot{q}_d + g(q_d) \]

6 Computational Efficiency Comparison

Method Complexity Application Scenario
Newton-Euler Recursion \(O(n)\) Real-time inverse dynamics, control
Lagrangian \(O(n^3) \sim O(n^4)\) Deriving symbolic expressions, theoretical analysis
Articulated-Body Algorithm \(O(n)\) Forward dynamics simulation
Composite-Rigid-Body \(O(n^2)\) Computing \(M(q)\) (paired with \(O(n)\) inverse dynamics)

7 Extended Topics

7.1 Contact Dynamics

When the robot makes contact with the environment, contact force constraints must be introduced:

\[ M(q)\ddot{q} + C(q,\dot{q})\dot{q} + g(q) = \tau + J_c^T F_c \]

where \(J_c\) is the contact Jacobian and \(F_c\) is the contact force. Contact forces must satisfy friction cone constraints, among others.

7.2 Flexible Joint Dynamics

When joints have elasticity (e.g., harmonic drives), the model must be extended:

\[ M(q)\ddot{q} + C\dot{q} + g = K(\theta_m - q) \]
\[ B\ddot{\theta}_m + K(\theta_m - q) = \tau_m \]

where \(K\) is the joint stiffness matrix, \(B\) is the motor inertia, and \(\theta_m\) is the motor-side angle.

7.3 Common Simulation Tools

  • MuJoCo: Efficient contact dynamics simulator, widely used in robot learning
  • PyBullet: Open-source physics engine with Python interface
  • Drake: Developed by MIT, supports multi-body dynamics and optimal control
  • Pinocchio: Efficient rigid body dynamics library with analytical derivatives

References

  1. Featherstone, R. (2008). Rigid Body Dynamics Algorithms. Springer.
  2. Siciliano, B. et al. (2009). Robotics: Modelling, Planning and Control. Springer.
  3. Craig, J. J. (2005). Introduction to Robotics: Mechanics and Control. Pearson.
  4. Spong, M. W. et al. (2006). Robot Modeling and Control. Wiley.

评论 #