5-Degree-Of-Freedom Robotic Manipulator

5-DOF robotic manipulator that detects, picks up and shoots a ping-pong ball into a hole

Project Overview


The 5-DOF Robotic Manipulator Project was the final project for MECH 440 - Robotics I at North Central College, where students applied their knowledge of kinematics, MATLAB simulations, and robotic path/trajectory planning to optimize and automate a robotic system.

The manipulator was preassembled before the project began, meaning our primary tasks were troubleshooting mechanical and electrical connections, performing kinematic calculations, developing MATLAB simulations, and programming the robot using Arduino. Unlike other aspects of robotic design, the dynamics of the system were pre-defined by the professor, so our focus was on ensuring the kinematic accuracy and functional performance of the manipulator.

The objective was to automate the pickup and placement of a ping-pong ball, with an additional mechanism to detect and shoot the ball into a target hole. Through troubleshooting, iterative optimization, and integration of ultrasonic sensors, PWM motor control, and automated decision-making, we developed a fully functional robotic system that outperformed other teams in the class.

Our team’s efforts led to a 100% success rate in ball placement and shooting in (20/20 tries), achieving first place in the class competition and earning the "Best Robotics Project - Fall 2024" award.

Predefined Specifications:

  1. At least five degrees of freedom manipulator.
  2. The robot manipulator should pick up a ping-pong ball from a pick-up location and place it to a predetermined placing location.
  3. When the ping-pong ball is in placing location, a system should be able to sense it and successfullyshoot it to a hole.
  4. Application of forward kinematics to find end-effector position and orientation for specific joint angles.5
  5. Application of inverse kinematics to find joint angle for specific end-effector position
  6. MATLAB simulation using robotics toolbox.Constraints:Minimum diameter of the load (ball) = 4 cmMaximum diameter of the hole = 8 cmMinimum distance of the hole from the placing location is 1 ft

Project Planning

Once the project was introduced, our first step was to strategically assign tasks based on each team member's strengths and experience. Since the 5-DOF robotic manipulator was preassembled, our focus was on troubleshooting, programming, kinematic analysis, and automation.

To ensure efficiency, we met after class to discuss our individual skill sets and how we could contribute to different aspects of the project. We divided responsibilities as follows:

  • One team member focused on kinematics and calculations, specifically handling Denavit-Hartenberg (DH) parameter tables, homogeneous transformation matrices, Jacobians, and MATLAB simulations to verify movement accuracy.
  • Another team member specialized in SolidWorks and mechanical design and also worked on kinematics, taking on tasks such as designing a 3D-printed casing for the ultrasonic sensor and working on the ball-kicking mechanism for the final stage of automation.
  • I took responsibility for programming the robotic system using Arduino, ensuring smooth motor control and integrating sensors for automation. Additionally, I assisted with the initial DH tables and MATLAB simulations to verify and troubleshoot the system’s movement logic.

By clearly defining roles early on, we streamlined the workflow and ensured that each aspect of the project was covered, which I believe was a key step that helped us to be successful on this project. Our next step was to test and troubleshoot the manipulator's hardware and connections, which became the first major challenge we had to overcome.

Initial Challenges & Setup

Before we could begin programming and optimizing the robotic manipulator, we first had to troubleshoot and resolve hardware issues. Since the manipulator was preassembled, we expected it to function correctly, but upon testing, we discovered multiple challenges that needed to be addressed:

Hardware Issues & Debugging

  • Some servo motors were not responding properly, while others were moving erratically.
  • Electrical connections were incorrectly wired, leading to misalignment and power inconsistencies.
  • Several screws in the joints were loose, affecting the stability and precision of movement.

To resolve these issues, we systematically:

  1. Tested each servo motor individually to ensure it was receiving the correct signals.
  2. Checked and rewired electrical connections, ensuring each motor was properly assigned to the correct joint.
  3. Tightened and secured mechanical components to improve stability and movement accuracy.

Once the hardware was functional, the next step was to map out each joint and the end effector, allowing us to define and control movement sequences accurately.

Early Coding & Movement Mapping

With the mechanical and electrical setup complete, we:

  • Programmed each servo motor separately to confirm they were working properly.
  • Identified and tested key positions required for the robot to complete the task:
    • Initial position
    • Pickup 1 (upper ball position) & Pickup 2 (up)
    • Intermediate position
    • Drop-off 1 (upper placement) & Drop-off 2 (bottom)

At this stage, the manipulator was successfully moving to defined positions, but was not yet optmized and would often fail to grab the ball properly (shown in video below). However, we were ready to proceed with kinematic modeling and simulation validation.

Kinematic & Simulation Analysis

With the robotic manipulator fully functional after troubleshooting, the next step was to develop accurate kinematic models and validate them through simulations. Since the system was preassembled, we needed to ensure that all joint movements were mathematically correct and that the end effector followed the desired trajectory.

Forward & Inverse Kinematics

To control the manipulator accurately, we:

  • Defined the Denavit-Hartenberg (DH) parameters to represent each joint’s position and orientation.
  • Used homogeneous transformation matrices (HTMs) to derive the end-effector’s position and orientation for given joint angles (Forward Kinematics).
  • Applied Inverse Kinematics calculations to determine the required joint angles for a given end-effector position.

Velocity Kinematics & Jacobians

Once the basic kinematic models were established, we:

  • Derived the Jacobian matrices (Jv and Jw) to analyze velocity relationships between joints and the end effector.
  • Verified our equations by comparing manual calculations to MATLAB simulations.

MATLAB Simulations & Path Planning

To validate our kinematic solutions, we:

  • Used Peter Corke’s MATLAB Robotics Toolbox to simulate and visualize the manipulator’s movement.
  • Conducted path and trajectory planning simulations, ensuring that the end effector followed a smooth and precise motion.
  • Adjusted our calculations based on simulation results, refining the robot’s accuracy before implementing movement in the actual system.

Mechanical Design & Hardware

With the kinematic models and simulations validated, we shifted our focus to enhancing the physical system by integrating additional hardware components to improve automation and functionality.

3D Modeling & Hardware Modifications

Although the robotic manipulator was preassembled, we made key modifications to enhance its performance, including:

  • Adding an ultrasonic sensor casing to protect and position the sensor for accurate object detection.
  • Designing and implementing a ball-kicking mechanism to ensure the ball was successfully launched into the hole after placement.
  • Adding soft EVA foam to hold the ball at pickup and dropoff locations.

Sensor Integration & Automation Enhancements

To make the robotic manipulator more autonomous, we integrated ultrasonic sensors at two key locations:

  1. Pickup Location Sensor: Detected when a ball was present, triggering the robotic manipulator to begin the pickup process.
  2. Drop-off Location Sensor: Verified that the ball had been placed correctly before activating the ball-kicking mechanism.

PWM Implementation for Smoother Movements

At this stage, we implemented Pulse Width Modulation (PWM) control for the servo motors, allowing us to:

  • Reduce jerky movements and ensure the ball would not fall off.
  • Optimize servo speed and acceleration, improving efficiency and accuracy.
  • Prevent unnecessary stress on the motors, enhancing the system’s longevity.

Final Arduino code is attached to the bottom of this post.

By modifying the hardware, integrating sensors, and refining motor control, we significantly improved the manipulator’s automation capabilities, preparing it for final testing and optimization.

The video below shows the manipulator succesfully completing all the movements(but without the ultrasonic sensors):

Testing & Final Performance

After completing the mechanical modifications, sensor integration, and programming, we conducted extensive testing and performance evaluations to ensure the robotic manipulator operated as intended.

Final System Testing

The final version of our robotic manipulator successfully completed the entire automated sequence:
Detecting the ball at the pickup location (ultrasonic sensor activation)
Picking up the ball using precise servo-controlled movements
Moving to the intermediate position for a smooth transition
Placing the ball at the designated drop-off location
Detecting the ball at the drop-off using the second ultrasonic sensor
Kicking the ball into the hole with the ball-shooting mechanism

Through rigorous testing, we refined the sensor response times, adjusted motor speeds, and fine-tuned position accuracy to achieve a highly consistent and efficient system.

Final Performance Results

  • 100% success rate in detecting, picking up, and placing the ball.
  • Consistently completed the full sequence in just 16 seconds per cycle (from the moment the ball is detected to the moment it gets into the hole)
  • Automated process with no manual intervention required (after ball placement)
  • Awarded "Best Robotics Project - Fall 2024" for achieving the best performance among all competing teams.

The video below showcases the final robotic manipulator system successfully completing all movements, demonstrating the smooth operation and efficiency of our design.

Conclusion & Learnings

The 5-DOF Robotic Manipulator Project was a challenging yet rewarding experience that strengthened our understanding of robotic automation, kinematics, and system integration. Through troubleshooting, coding, sensor integration, and MATLAB simulations, we transformed a preassembled manipulator into an autonomous system capable of efficiently completing a complex task.

Key Takeaways

  • Robotics & Automation: Gained hands-on experience in robot programming, sensor integration, and motor control optimization using Arduino and MATLAB.
  • Kinematic Modeling & Simulations: Applied forward and inverse kinematics, Jacobians, and trajectory planning to ensure accurate and smooth robotic movements.
  • Problem-Solving & Debugging: Developed critical troubleshooting skills by resolving electrical, mechanical, and software issues to optimize system performance.
  • System Optimization: Implemented PWM motor control to improve movement precision and enhance automation using ultrasonic sensors for object detection.
  • Team Collaboration: Successfully divided and executed tasks, ensuring efficient workflow and technical contributions from each team member.

The final result was an automated system that performed very well, earning us the "Best Robotics Project - Fall 2024" award. This project reinforced our ability to integrate engineering concepts into a real-world application, further preparing us for careers in robotics, automation, and mechanical design.

"Best Robotics Project - Fall 2024" award

A special thank you to North Central College for providing the necessary components, tools, and facilities that made this project possible.

Bill of Materials (BOM) & Arduino Code
Bill of Materials (BOM)

Final Arduino Code:

#include <Adafruit_PWMServoDriver.h>

// Initialize the PCA9685 board with the default I2C address (0x40)
Adafruit_PWMServoDriver board1 = Adafruit_PWMServoDriver(0x40);

// Define minimum and maximum pulse lengths for the servos
#define SERVOMIN 125  // Minimum pulse length count (out of 4096)
#define SERVOMAX 625  // Maximum pulse length count (out of 4096)

// Ultrasonic sensor pins
const int trigPin = 9;
const int echoPin = 10;
const int trigPinPickup = 11;  // Trig pin for second ultrasonic sensor
const int echoPinPickup = 12;  // Echo pin for second ultrasonic sensor


// Function to convert an angle (0-180) into the corresponding PWM pulse
int angleToPulse(int ang) {
  int pulse = map(ang, 0, 180, SERVOMIN, SERVOMAX);  // Map angle 0-180 to pulse width
  return pulse;
}

// Function to calculate distance using ultrasonic sensor
float getDistance(int trigPin, int echoPin) {
  digitalWrite(trigPin, LOW);
  delayMicroseconds(2);
  digitalWrite(trigPin, HIGH);
  delayMicroseconds(10);
  digitalWrite(trigPin, LOW);

  long duration = pulseIn(echoPin, HIGH);
  float distance = duration * 0.034 / 2;  // Convert duration to distance in cm

  return distance;
}

void setup() {
  Serial.begin(9600);
  Serial.println("6-Servo Robotic Arm Test!");

  // Ultrasonic sensor setup
  pinMode(trigPin, OUTPUT);
  pinMode(echoPin, INPUT);
  pinMode(trigPinPickup, OUTPUT);  // Second ultrasonic sensor
  pinMode(echoPinPickup, INPUT);   // Second ultrasonic sensor

  board1.begin();
  board1.setPWMFreq(60);  // Set frequency to 60 Hz for the servos
}

// Channels for each servo
#define theta1 0    // BASE_SERVO_CHANNEL
#define theta2 1    // LIFT_SERVO_CHANNEL
#define theta3 2    // ROTATE_SERVO_CHANNEL
#define theta4 3    // BEND_SERVO_CHANNEL
#define theta5 4    // END_EFFECTOR_ROTATE_CHANNEL
#define EE_ANGLE 5  // CLAW_SERVO_CHANNEL
#define kickAngle 6 // KICK SERVO_CHANNEL

// Function to move servo smoothly by incrementing PWM pulse
void moveServoSmoothPWM(int channel, int startPulse, int endPulse, int increment, int stepDelay) {
  if (startPulse < endPulse) {
    for (int pulse = startPulse; pulse <= endPulse; pulse += increment) {
      board1.setPWM(channel, 0, pulse);
      delay(stepDelay);  // Small delay to control speed
    }
  } else {
    for (int pulse = startPulse; pulse >= endPulse; pulse -= increment) {
      board1.setPWM(channel, 0, pulse);
      delay(stepDelay);  // Small delay to control speed
    }
  }
}

void loop() {




  //INITIAL POSITION
  //
 
  delay(500);
  moveServoSmoothPWM(theta2, angleToPulse(140), angleToPulse(115), 1, 20);
  delay(500);


  moveServoSmoothPWM(theta3, angleToPulse(140), angleToPulse(140), 1, 20);


  moveServoSmoothPWM(theta4, angleToPulse(140), angleToPulse(130), 1, 20);



  moveServoSmoothPWM(theta1, angleToPulse(145), angleToPulse(145), 1, 20);
  

  moveServoSmoothPWM(theta5, angleToPulse(166), angleToPulse(166), 1, 20);
  
  moveServoSmoothPWM(EE_ANGLE, angleToPulse(50), angleToPulse(50), 1, 20);
  delay(500);

// // Wait until a ball is detected at the pickup location
// Serial.println("Waiting for ball at the pickup location...");
// float pickupDistance = getDistance(trigPinPickup, echoPinPickup);




//
while (true) {  // Infinite loop to wait for the ball
  float distance = getDistance(trigPinPickup, echoPinPickup);
  Serial.print("Distance: ");
  Serial.print(distance);
  Serial.println(" cm");

  if (distance <= 7) {  // If the ball is detected within 6 cm
    // Ball detected, proceed with the pickup sequence
    Serial.println("Ball detected at the pickup location. Starting pickup sequence.");
    break;  // Exit the loop once the ball is detected 
  } else {
    Serial.println("No ball detected. Waiting...");
    delay(500);  // Wait before checking again to avoid excessive CPU usage
  }

}
//

delay(500);


// PICKUP POSITION (TOP1)
moveServoSmoothPWM(theta2, angleToPulse(115), angleToPulse(115), 1, 20);
moveServoSmoothPWM(theta3, angleToPulse(140), angleToPulse(140), 1, 20);
moveServoSmoothPWM(theta4, angleToPulse(140), angleToPulse(140), 1, 20);
moveServoSmoothPWM(theta1, angleToPulse(180), angleToPulse(180), 1, 20);
moveServoSmoothPWM(theta5, angleToPulse(166), angleToPulse(166), 1, 20);
moveServoSmoothPWM(EE_ANGLE, angleToPulse(50), angleToPulse(50), 1, 20);
delay(500);




  //PICKUP POSITION (BOTTOM)
  //


  // Move rotate servo from 115 to 104 degrees, with PWM increment of 1 and 20ms delay
  moveServoSmoothPWM(theta2, angleToPulse(115), angleToPulse(104), 1, 10);
  delay(150);

  moveServoSmoothPWM(theta3, angleToPulse(140), angleToPulse(140), 1, 20);


  moveServoSmoothPWM(theta4, angleToPulse(140), angleToPulse(140), 1, 20);


  
  moveServoSmoothPWM(theta1, angleToPulse(180), angleToPulse(180), 1, 20);


  moveServoSmoothPWM(theta5, angleToPulse(166), angleToPulse(166), 1, 20);

  moveServoSmoothPWM(EE_ANGLE, angleToPulse(50), angleToPulse(50), 1, 20);


  //CLOSE THE END-EFFECTOR

  moveServoSmoothPWM(EE_ANGLE, angleToPulse(85), angleToPulse(85), 1, 20);
  delay(800);
  


  //PICKUP POSITION (TOP2)
  //


  moveServoSmoothPWM(theta2, angleToPulse(115), angleToPulse(115), 1, 20);


  moveServoSmoothPWM(theta3, angleToPulse(140), angleToPulse(140), 1, 20);


  moveServoSmoothPWM(theta4, angleToPulse(140), angleToPulse(140), 1, 20);


  
  moveServoSmoothPWM(theta1, angleToPulse(180), angleToPulse(180), 1, 20);
  

  moveServoSmoothPWM(theta5, angleToPulse(166), angleToPulse(166), 1, 20);

  moveServoSmoothPWM(EE_ANGLE, angleToPulse(85), angleToPulse(85), 1, 20);
  delay(500);





  //INTERMEDIATE POSITION
  //


  moveServoSmoothPWM(theta2, angleToPulse(140), angleToPulse(140), 1, 20);


 
  moveServoSmoothPWM(theta3, angleToPulse(140), angleToPulse(140), 1, 20);


  moveServoSmoothPWM(theta4, angleToPulse(105), angleToPulse(105), 1, 20);



  moveServoSmoothPWM(theta1, angleToPulse(180), angleToPulse(80), 1, 5);


  moveServoSmoothPWM(theta5, angleToPulse(166), angleToPulse(166), 1, 20);

  moveServoSmoothPWM(EE_ANGLE, angleToPulse(85), angleToPulse(85), 1, 20);



  //DROPOFF LOCATION (TOP)
  //
// Move rotate servo from 105 to 140 degrees, with PWM increment of 1 and 20ms delay
  moveServoSmoothPWM(theta4, angleToPulse(105), angleToPulse(140), 1, 20);
  // Move rotate servo from 140 to 115 degrees, with PWM increment of 1 and 20ms delay
  moveServoSmoothPWM(theta2, angleToPulse(140), angleToPulse(115), 1, 20);




  moveServoSmoothPWM(theta3, angleToPulse(140), angleToPulse(140), 1, 20);





  // Move base servo from 80 to 108 degrees, with PWM increment of 1 and 20ms delay
  moveServoSmoothPWM(theta1, angleToPulse(80), angleToPulse(108), 1, 20);

  moveServoSmoothPWM(theta5, angleToPulse(166), angleToPulse(166), 1, 20);

  moveServoSmoothPWM(EE_ANGLE, angleToPulse(85), angleToPulse(85), 1, 20);


  //DROPOFF POSITION (BOTTOM)
  //

// Move rotate servo from 115 to 104 degrees, with PWM increment of 1 and 20ms delay
  moveServoSmoothPWM(theta2, angleToPulse(115), angleToPulse(104), 1, 15);
  delay(100);

  
  moveServoSmoothPWM(theta3, angleToPulse(140), angleToPulse(140), 1, 20);


  moveServoSmoothPWM(theta4, angleToPulse(140), angleToPulse(140), 1, 20);


  
  moveServoSmoothPWM(theta1, angleToPulse(108), angleToPulse(108), 1, 20);


  moveServoSmoothPWM(theta5, angleToPulse(166), angleToPulse(166), 1, 20);

  moveServoSmoothPWM(EE_ANGLE, angleToPulse(50), angleToPulse(50), 1, 20);
  delay(500);









  //DROPOFF LOCATION (TOP2)
  //

  moveServoSmoothPWM(theta4, angleToPulse(140), angleToPulse(140), 1, 20);
  // Move rotate servo from 105 to 115 degrees, with PWM increment of 1 and 20ms delay
  moveServoSmoothPWM(theta2, angleToPulse(105), angleToPulse(115), 1, 10);




 
  moveServoSmoothPWM(theta3, angleToPulse(140), angleToPulse(140), 1, 20);





  
  moveServoSmoothPWM(theta1, angleToPulse(108), angleToPulse(108), 1, 20);


  moveServoSmoothPWM(theta5, angleToPulse(166), angleToPulse(166), 1, 20);

  moveServoSmoothPWM(EE_ANGLE, angleToPulse(50), angleToPulse(50), 1, 20);
  

// PRE INITIAL POSITION
  
  moveServoSmoothPWM(theta2, angleToPulse(115), angleToPulse(140), 1, 20);
  

  moveServoSmoothPWM(theta3, angleToPulse(140), angleToPulse(140), 1, 20);

  moveServoSmoothPWM(theta4, angleToPulse(140), angleToPulse(130), 1, 20);

  moveServoSmoothPWM(theta1, angleToPulse(145), angleToPulse(145), 1, 20);

  moveServoSmoothPWM(theta5, angleToPulse(166), angleToPulse(166), 1, 20);

  moveServoSmoothPWM(EE_ANGLE, angleToPulse(50), angleToPulse(50), 1, 20);
  delay(1000);

  // Ultrasonic sensor check
Serial.println("Waiting for the ball...");

while (true) {  // Infinite loop to wait for the ball
  float distance = getDistance(trigPin, echoPin);
  Serial.print("Distance: ");
  Serial.print(distance);
  Serial.println(" cm");

  if (distance <= 6) {  // If the ball is detected within 6 cm
    Serial.println("Ball detected! Moving kick servo.");
    moveServoSmoothPWM(kickAngle, angleToPulse(90), angleToPulse(180), 15, 15); // Kick action
    delay(100);
    moveServoSmoothPWM(kickAngle, angleToPulse(180), angleToPulse(90), 10, 15); // Return to default
    delay(500);
    break;  // Exit the loop once the ball is detected and kicked
  } else {
    Serial.println("No ball detected. Waiting...");
    delay(500);  // Wait before checking again to avoid excessive CPU usage
  }

}




}