Shourya's Project
Robotic Arm: Assembly, Kinematics, and Control

Robotic Arm: Assembly, Kinematics, and Control

Shourya Shourya
July 25, 2024
7 min read
Table of Contents

Robotic Arm: Assembly, Kinematics, and Control

1. Introduction

A robotic arm is a multi-degree-of-freedom (DOF) mechanical system, capable of performing precise movements in various industrial and research applications.

In this article, we explore the design, kinematics, and control mechanisms for a 5-DOF robotic arm, covering:

  • Degrees of Freedom (DOF) and how they impact motion
  • Forward & Inverse Kinematics calculations
  • Control mechanisms (Open-loop & Closed-loop)

2. Understanding Degrees of Freedom (DOF)

A robotic arm’s DOF defines how many independent movements it can perform. Each joint adds one rotational or translational movement.

To understand DOF, let’s compare with the human arm:

  1. Shoulder (3 DOF): Moves in pitch (up/down), yaw (left/right), and roll (twisting).
  2. Elbow (1 DOF): Bends the arm (pitch movement).
  3. Wrist (2 DOF): Moves up/down (pitch) and rotates (roll).
  4. Fingers (Multiple DOF): Used for gripping objects.

For our 5-DOF robotic arm, the movement is as follows:

JointFunctionMotion TypeMotor Type
BaseRotation (Yaw)RotationalStepper Motor
ShoulderUp/Down (Pitch)RotationalServo / Stepper
ElbowBending (Pitch)RotationalServo / Stepper
WristRotation (Roll)RotationalServo
End-EffectorGripping / ToolRotational / GraspServo / Pneumatic

3. Kinematics

Kinematics deals with the movement of the robotic arm without considering forces. We analyze:

  • Forward Kinematics (FK): Finding the end-effector position from joint angles.
  • Inverse Kinematics (IK): Computing required joint angles for a target position.

3.1 Forward Kinematics (FK)

FK is calculated using Denavit-Hartenberg (DH) parameters, which define joint transformations in matrix form.

Tii1=[cosθisinθicosαisinθisinαiaicosθisinθicosθicosαicosθisinαiaisinθi0sinαicosαidi0001]T_{i}^{i-1} = \begin{bmatrix} \cos\theta_i & -\sin\theta_i\cos\alpha_i & \sin\theta_i\sin\alpha_i & a_i\cos\theta_i \\ \sin\theta_i & \cos\theta_i\cos\alpha_i & -\cos\theta_i\sin\alpha_i & a_i\sin\theta_i \\ 0 & \sin\alpha_i & \cos\alpha_i & d_i \\ 0 & 0 & 0 & 1 \end{bmatrix}

Where:

  • θi\theta_i = Joint angle
  • αi\alpha_i = Link twist
  • aia_i = Link length
  • did_i = Link offset

FK helps us determine the final position (X,Y,Z)(X, Y, Z) based on joint rotations.

3.2 Inverse Kinematics (IK)

IK solves for joint angles given a desired end-effector position. It can be solved using:

  • Geometric Method (for simple cases)
  • Jacobian Matrix & Pseudoinverse (for complex arms)
  • Numerical Optimization (Gradient Descent, Newton-Raphson)

IK Calculation Example for a 2-DOF Arm

import numpy as np
 
def inverse_kinematics(x, y, l1, l2):
    D = (x**2 + y**2 - l1**2 - l2**2) / (2 * l1 * l2)
    
    if abs(D) > 1:
        raise ValueError("Target is out of reach")
    
    theta2 = np.arctan2(np.sqrt(1 - D**2), D)  # Elbow angle
    theta1 = np.arctan2(y, x) - np.arctan2(l2 * np.sin(theta2), l1 + l2 * np.cos(theta2))
    
    return np.degrees(theta1), np.degrees(theta2)
 
# Example: Target (x=10, y=10), arm lengths l1=10, l2=10
theta1, theta2 = inverse_kinematics(10, 10, 10, 10)
print(f"Joint Angles: θ1={theta1:.2f}, θ2={theta2:.2f}")
 
---
 
## **4. Control System**
 
### **4.1 Open-Loop Control (Basic Servo Control)**
A simple method where predefined angles are sent without feedback.
 
```cpp
#include <Servo.h>
Servo servo1;
 
void setup() {
    servo1.attach(9);
}
 
void loop() {
    servo1.write(90); // Move to 90 degrees
    delay(1000);
}

4.2 Closed-Loop Control (PID Feedback)

Uses encoders + PID Controllers for precise movement correction.

import time
import PID
 
pid = PID.PID(1.2, 0.01, 0.2)
pid.SetPoint = 90  # Desired angle
 
while True:
    feedback = get_encoder_angle()
    output = pid.update(feedback)
    motor_control(output)
    time.sleep(0.1)

Advantages of Closed-Loop Control:

  • More precise positioning
  • Error correction using sensors
  • Adaptive learning with AI integration

4.3 PID Control: The Brain of Precision Movement

A PID (Proportional-Integral-Derivative) Controller is an algorithm used in control systems to maintain a system at a desired state by continuously adjusting inputs based on feedback. It’s widely used in robotics, industrial automation, and aerospace applications.

4.3.1 What is PID Control?

PID stands for:

  • Proportional (P): Reacts to the current error.
  • Integral (I): Reacts to the accumulated error over time.
  • Derivative (D): Reacts to the rate of change of error.

It continuously calculates an error value ( e(t) ), which is the difference between the desired setpoint and the actual measured value. The PID controller then adjusts the system’s output to minimize this error.


4.3.2 The PID Equation

The control output ( u(t) ) is given by:

u(t)=Kpe(t)+Kie(t)dt+Kdddte(t)u(t) = K_p e(t) + K_i \int e(t) dt + K_d \frac{d}{dt} e(t)

Where:

  • ( e(t) ) = Setpoint – Actual Value (Error)
  • ( K_p ) = Proportional Gain
  • ( K_i ) = Integral Gain
  • ( K_d ) = Derivative Gain

Each term has a specific role:

TermFunction
Proportional (P)Reacts to current error. Larger error → Larger correction.
Integral (I)Accumulates past errors. Helps remove steady-state errors.
Derivative (D)Predicts future errors based on rate of change. Reduces overshoot.

4.3.3 Understanding Each Term

(a) Proportional Control (P)
  • Adjusts the output proportional to the error.
  • If error is large, correction is strong; if error is small, correction is weak.
  • However, P alone cannot eliminate steady-state error.

[ u(t) = K_p e(t) ]

🔹 Example: If a robotic arm is 10° away from the target, P control applies a force proportional to 10°. If it’s 1° away, the force is 10x smaller.


(b) Integral Control (I)
  • Accumulates past errors and applies corrections.
  • Helps eliminate steady-state errors.
  • However, too much I can cause overshoot.

[ u(t) = K_i \int e(t) dt ]

🔹 Example: If a robotic arm consistently stops slightly short of the target, the integral term accumulates the small errors and compensates.


(c) Derivative Control (D)
  • Predicts future error trends by analyzing the rate of change.
  • Reduces overshoot and improves stability.
  • However, too much D can amplify noise.
u(t)=Kpe(t)+Kie(t)dt+Kdddte(t)u(t) = K_p e(t) + K_i \int e(t) dt + K_d \frac{d}{dt} e(t)

🔹 Example: If the robotic arm moves too fast toward the target, the derivative term slows it down, preventing overshoot.


4.3.4 PID Tuning (Choosing ( K_p ), ( K_i ), ( K_d ))

Tuning PID means finding the best ( K_p ), ( K_i ), ( K_d ) values for a system. Common tuning methods:

  • Manual Tuning: Trial and error.
  • Ziegler-Nichols Method: Uses system response.
  • Auto-Tuning Algorithms: AI-based optimization.

A well-tuned PID controller ensures:

  • Fast response
  • Minimal overshoot
  • Accurate positioning

5. Potential Upgrades

  • Computer Vision (OpenCV + YOLO) – Object tracking.
  • ROS Integration – Advanced motion planning.
  • Haptic Feedback – Real-time force sensing.
  • AI-powered Motion Prediction – Adaptive learning.
  • Wireless Control (ESP-NOW / BLE) – Remote operation.

6. Conclusion

This robotic arm project demonstrates a comprehensive understanding of mechanical assembly, kinematics, and control algorithms. Future developments will focus on AI integration, real-time feedback, and enhanced autonomy for industrial and research applications.

Robotic Arm 3D Model

i will provide that soon