How To Perform a Pick and Place Task With a DIY SCARA Robot

In this tutorial, we will program our robot to perform a pick and place task.

Pick and place involves picking up an object in one location and placing it in another.

In this case, we will have our do-it-yourself SCARA robotic arm pick up a hex nut in one location and drop it off in another. Take a look at the video below of what you will build.

Real-World Applications

SCARA robots have a number of real-world applications: 

  • Manufacturing: Picking up items off a conveyor belt and dropping them off on another conveyor belt.
  • Logistics: Picking up an item and placing it in a bin.
  • Factory: Tightening screws.

You can see an image here of a SCARA robot packaging cookies into bins.

scara-robot-packaging-cookies
Source: Gfycat

Prerequisites

  • You completed this tutorial to build a two degree of freedom robotic arm.

You Will Need

Assuming you have gone through the prerequisites and acquired all the components in there, you will also need the following components to complete this project (#ad):

  • 5V or 6V Electric Lifting Magnet (electromagnet to pick up the nut)
  • Actuonix L16 Actuator 100mm 150:1 6V RC Control (linear actuator…check on eBay for this)
  • 22 gauge wire spool (to tie the actuator to the end of the end effector of the robotic arm)
  • Small Hex Nut or a Screw (any size is OK) or Any Small Object Made of Metal
  • 5V Relay (only needed if you’re going to buy the 6V Electric Lifting Magnet)
  • 6 Channel Servo Tester
  • Toy Trash Can
  • 2 x Oblique U-type Robotic Arm Brackets (check eBay and Amazon)
  • M3 Screws and Nuts (3mm in diameter screws)
  • VELCRO Brand Thin Clear Dots with Adhesive 

Connect and Test the Linear Actuator

The first thing you need to do is to replace the upper link of the robot arm with U-type robotic arm brackets.

2020-10-08-140824

Attach the linear actuator to the brackets using VELCRO Brand Thin Clear Dots with Adhesive. My setup looks like this:

2020-10-08-141309
2020-10-08-141327
2020-10-08-141423
2020-10-08-141429

We now have our very own SCARA-style robot.

Let’s test it. The linear actuator has the following specifications:

  • Input voltage: 5-7.4V
  • Stall current: 650mA

Grab the 6 channel digital servo tester. 

Connect the positive red lead to the positive terminal of the power supply.

Connect the negative black lead to the negative terminal of the power supply.

Connect the linear actuator to the digital servo tester so that the:

  • Black lead connects to (-)
  • Red lead connects to (+)
  • White lead connects to (S), which means signal

Now turn on the power supply. Set it to 6.0V with a current limit of 0.50A (ie. 500mA).

2020-10-08-141545

Turn the corresponding knob on the digital servo tester, and watch the linear actuator go back and forth.

2020-10-08-141948
2020-10-08-142006-1

Control the Linear Actuator Using Arduino

Now we want to write code so that we can automatically control the lowering and raising of the linear actuator. We will write code that makes the linear actuator go back and forth repeatedly. 

Open your Arduino IDE, and type the following code. Save the file as control_linear_actuator.ino.

/*
Program: Make a linear actuator go back and forth automatically
File: control_linear_actuator.ino
Description: This program makes the Actuonix L16 Actuator 100mm 150:1 6V RC Control 
  go back and forth.
Author: Addison Sears-Collins
Website: https://automaticaddison.com
Date: October 5, 2020
*/
 
#include <VarSpeedServo.h> 

//////////// Linear Actuator Variables ///////////////
// Create the object.
VarSpeedServo linearActuator; 

// Attach motor to digital pin on the Arduino
const int linearActuatorPin = 12;

// Set the home and extended positions of the linear actuator
const int linearActuatorHomePos = 0;
const int linearActuatorExtPos = 180;

// Stores the current position of the linear actuator
int linearActuatorPos = 0;

// The amount of time in milliseconds alloted to enable the linear actuator to move into position
// The more delay given, the more the linear actuator extends. 100ms, for example, will result
// in full extension of the linear actuator.
const int linearActuatorDelay = 50;
//////////// End Linear Actuator Variables ///////////////

void setup() {  

    // Attach the linear actuator to the pin 
    linearActuator.attach(linearActuatorPin);  
}
 
void loop() {  

  // Linear actuator goes to extended position and then back to home position
  moveLinearActuator();
}

void moveLinearActuator() {
  
  for (linearActuatorPos = linearActuatorHomePos; linearActuatorPos <= linearActuatorExtPos; linearActuatorPos += 1) { // goes from home position to extended position
    linearActuator.write(linearActuatorPos);       
    delay(linearActuatorDelay);  // wait for the actuator to reach the position
  }
  for (linearActuatorPos = linearActuatorExtPos; linearActuatorPos >= linearActuatorHomePos; linearActuatorPos -= 1) { // goes from extended position to home position
    linearActuator.write(linearActuatorPos);          
    delay(linearActuatorDelay);  // wait for the actuator to reach the position
  }  
}

Wire the linear actuator to the Arduino Mega 2560 like what is shown in wiring_linear_actuator_v2.pdf.

Turn on the power supply (6.0V with a current limit of 0.50A), and then plug in the Arduino to the 9V battery. Watch the linear actuator go back and forth.

So that you don’t damage your Arduino Mega, turn off the DC external power supply first before unplugging the Arduino.

Test the Electric Lifting Magnet

Now that we’ve tested the linear actuator, let’s test the electric lifting magnet. 

Grab the electric lifting magnet.

2020-10-08-192254

Attach the positive (typically red) lead of the magnet to the red positive lead of the power supply.

Attach the other lead (typically blue or black) of the magnet to the black lead of the power supply.

Set the voltage to 5V (or 6V depending on what it says on your magnet) and the current limit to 0.50A (the current limit of this component is 0.68A).

Turn on the power supply.

Grab a small metal object like a screw or hex nut, and place it near the magnet.

You should see the hex nut move towards the magnet.

If you are using a 5V electric lifting magnet, you can power the magnet directly with the Arduino by placing the leads in the 5V and GND (ground) pins.

2020-10-08-192237
2020-10-08-192243

Control the Electric Lifting Magnet Using Arduino

Now let’s control the electric lifting magnet using Arduino. 

Using a 6V Electric Lifting Magnet

If you have a 6V electric lifting magnet, follow the instructions in this section. Otherwise, if you’re using a 5V electric lifting magnet, proceed to the next section.

Grab the 5V Relay. This relay acts as a switch for the electric lifting magnet, enabling you to activate and deactivate the magnetism using Arduino.

There are 6 pins on the relay:

  • NO: Normally Open Terminal (peak load of DC28~30V/10A)
  • NC: Normally Closed Terminal
  • COM: Common Terminal
  • DC+: Connects to the 5V pin (power supply) of the Arduino
  • DC-: Connects to the GND (ground) pin of the Arduino
  • IN: Control pin that receives either a HIGH (3-5V) or LOW (0-1.5V) signal from the Arduino (Pin 10 in our case)

If you decide to use the NO terminal instead of the NC terminal, when a HIGH signal is received on the IN pin from the Arduino, the relay switch will turn ON, allowing electric current to flow from C to NO. We’ll use this NO terminal in our work.

If you decide to use the NC terminal instead of the NO terminal, when a LOW signal is received on the IN pin from the Arduino, the relay switch will turn ON allowing electric current to flow from C to NC.

Here is how to wire the relay: control_electric_magnet_arduino_v1.pdf.

Here is the code to test the setup: control_electric_magnet_arduino_v1.ino.

/*
Program: Make an electric lifting magnet turn ON and OFF repeatedly.
File: control_electric_magnet_arduino_v1.ino
Description: This program makes an electric lifting magnet turn ON and OFF repeatedly.
Author: Addison Sears-Collins
Website: https://automaticaddison.com
Date: October 6, 2020
*/

const int magnetSignalPin = 10;    // select the pin that will control the magnet

void setup() {
  pinMode(magnetSignalPin, OUTPUT);    // sets digital pin 10 as output
}

void loop() {
  activateMagnet();
  delay(10000);            // waits for 10 seconds
  deactivateMagnet();
  delay(3000);            // wait for 3 seconds
}

void activateMagnet() {  
  digitalWrite(magnetSignalPin, HIGH); // sets the digital pin ON  
}

void deactivateMagnet() {  
  digitalWrite(magnetSignalPin, LOW); // sets the digital pin OFF  
}

Using a 5V Electric Lifting Magnet

If you’re using the 5V electric lifting magnet, wire your system as follows: control_electric_magnet_arduino_v2.pdf.

For your Arduino, you’ll need to upload the same code from the previous section: control_electric_magnet_arduino_v1.ino.

Your magnet will activate for 10 seconds and then deactivate for 3 seconds.

2020-10-08-192455

Connect the Electric Lifting Magnet to the Linear Actuator

Now that we’ve tested the electric lifting magnet, let’s connect it to the end of the linear actuator. I placed a 3mm diameter screw in one side of the magnet so that it can more easily attach to the end of the linear actuator. 

2020-10-08-213249
2020-10-08-220256

Perform Pick and Place Using Arduino

Before we dive into the pick and place task, let’s see how to perform pick and place using Arduino and our robotic arm. Check out this tutorial for the details on the math.

What we want to do is:

  • Place a hex nut at a predetermined x and y coordinate. This is the pick location.
  • Move the end effector to the pick location.
  • Activate the electric lifting magnet.
  • Lower the linear actuator.
  • Pick up the hex nut.
  • Raise the linear actuator.
  • Move the end effector to the place location.
  • Deactivate the electric lifting magnet.
  • Place the hex nut in the toy trash can by lowering the actuator.
  • Return to the home position (both servos at 0 degrees).

To get started, measure the link lengths, a1, a2, a3, and a4. Use the kinematic diagram below as your guide. You’ll need to use a ruler for this. 

  • a1 is measured vertically from the board’s surface to the top of Link 2. 
  • a2 is measured horizontally from the middle of the first servo (where the central screw is located on Joint 1) to the middle of the second servo (where the central screw on Joint 2 is located).
  • a3 is measured vertically from the top of Link 2 to the top of Link 4.
  • a4 is measured horizontally from the middle of the second servo to the middle of the electric lifting magnet.
33-add-y-axisJPG

Place a metal object (e.g. hex nut) at position x = 4.0, y = 10.0 on the board.

Place the toy trash cash at position x = -4.0, y = 10.0.

2020-10-09-193231

Here is the wiring diagram: pick_and_place_no_vision_v1.pdf.

Set the power supply to 6V with a 0.60A current limit.

2020-10-09-193250
2020-10-09-193710

Here is the code for the Arduino:  pick_and_place_no_vision.ino.

/*
Program: Perform a pick and place task with a SCARA-style robotic 
  arm using inverse kinematics (graphical method)
File: pick_and_place_no_vision_v1.ino
Description: This program performs a pick and place task with a SCARA-style robotic arm. 
  No computer vision is used.
Author: Addison Sears-Collins
Website: https://automaticaddison.com
Date: October 9, 2020
*/
 
#include <VarSpeedServo.h> 

//////////// Servo Motor Variables ///////////////

// Define the number of servos
#define SERVOS 2

// Create the servo objects.
VarSpeedServo myservo[SERVOS]; 

// Speed of the servo motors
// Speed=1: Slowest
// Speed=255: Fastest.
const int servoSpeed = 50;

// Attach servos to digital pins on the Arduino
int servoPins[SERVOS] = {3,5};

//////////// End Servo Motor Variables ///////////////

//////////// Linear Actuator Variables ///////////////

// Create the linear servo object.
VarSpeedServo linearActuator; 

// Attach motor to digital pin on the Arduino
const int linearActuatorPin = 12;

// Set the home position of the linear actuator
const int linearActuatorHomePos = 0;

// Stores the current position of the linear actuator
int linearActuatorPos = 0;

// The amount of time in milliseconds alloted to enable the linear actuator to move into position
// The more delay given, the more the linear actuator extends. 100ms, for example, will result
// in full extension of the linear actuator. Tweak this input here until you get desired results.
const int linearActuatorDelay = 45;

//////////// End Linear Actuator Variables ///////////////

// Link lengths in centimeters
const double a1 = 4.85;
const double a2 = 5.80;
const double a3 = 5.15;
const double a4 = 6.0;

// Select the pin that will control the magnet
const int magnetSignalPin = 10;    

void setup() {

  // Move servos to the home position of 0 degrees
  setupServos(); 

  // Set magnet pin
  pinMode(magnetSignalPin, OUTPUT);    

  // Attach the linear actuator to the digital pin of the Arduino 
  linearActuator.attach(linearActuatorPin);  
  linearActuator.write(0); 
  delay(1000); 
}
 
void loop() {

  // The pick location in centimeters in the 
  // robot's base frame (pick up the object from here)
  double xPosPick = 4.0;
  double yPosPick = 10.0;

  // The place location in centimeters in the 
  // robot's base frame (place the object here)
  double xPosPlace = -4.0;
  double yPosPlace = 10.0;

  // Pick up an object from one location, and place it in another
  pickAndPlace(xPosPick, yPosPick, xPosPlace, yPosPlace);

  while(1) {
    // Return home
    returnHome();
  }
}     

/*  This method converts the desired angle for Servo 1 into a control angle
 *  for Servo 1. It assumes that the 0 degree position on the kinematic
 *  diagram for Servo 1 is actually 90 degrees on the actual servo.
 *  The angle range for Servo 1 on the kinematic diagram is
 *  -90 to 90 degrees, with 0 degrees being the center position. 
 *  The actual servo range for the physical motor
 *  is 0 to 180 degrees. We convert the desired angle 
 *  to a value within that range.
 */
int calcServo1Angle (int inputAngle) {
  
  int result;

  result = map(inputAngle, -90, 90, 0, 180);

  return result;
}  

/* Move servos to the home position */
void setupServos() {
  
  // Attach the servos to the servo object 
  // attach(pin, min, max  ) - Attaches to a pin 
  //   setting min and max values in microseconds
  //   default min is 544, max is 2400  
  // Alter these numbers until both servos have a 
  //   180 degree range.
  myservo[0].attach(servoPins[0], 544, 2475);  
  myservo[1].attach(servoPins[1], 500, 2475); 

  // Set initial servo positions to home position
  myservo[0].write(0, servoSpeed, true);  
  myservo[1].write(calcServo1Angle(0), servoSpeed, true);

  // Wait to let servos get into position
  delay(3000);
}

/* Move arm to the x and y position indicated by the parameters */
void moveArm(double xPos, double yPos) {

  // Define the inverse kinematics variables
  double r1 = 0.0;
  double phi_1 = 0.0;
  double phi_2 = 0.0;
  double phi_3 = 0.0;
  double theta_1 = 0.0;
  double theta_2 = 0.0;
  
  /* Calculate the inverse kinematics*/
  // (1) r1  = square_root((x_0_2)^2 + (y_0_2)^2) 
  // Value is in centimeters
  r1 = sqrt((xPos * xPos) + (yPos * yPos));

  // (2) ϕ1 = arccos((a4^2 - r1^2 - a2^2)/(-2*r1*a2))
  // The returned value is in the range [0, pi] radians. 
  phi_1 = acos(((a4 * a4) - (r1 * r1) - (a2 * a2))/(-2.0 * r1 * a2));

  // (3) ϕ2 = arctan((y_0_2) / (x_0_2)) 
  // The atan2() function computes the principal value of the 
  // arc tangent of y/x, using the signs of both arguments to 
  // determine the quadrant of the return value. 
  // The returned value is in the range [-pi, +pi] radians.
  phi_2 = atan2(yPos, xPos);

  // (4) θ1 =  ϕ1 - ϕ2
  // Value is in radians
  theta_1 = phi_2 - phi_1;

  // (5) ϕ3 = arccos((r1^2 - a2^2 - a4^2)/(-2*a2*a4))
  // Value is in radians
  phi_3 = acos(((r1 * r1) - (a2 * a2) - (a4 * a4))/(-2.0 * a2 * a4));

  //(6) θ2 = 180° - ϕ3 
  theta_2 = PI - phi_3;
    
  /* Convert the joint (servo) angles from radians to degrees*/
  theta_1 = theta_1 * RAD_TO_DEG; // Joint 1
  theta_2 = theta_2 * RAD_TO_DEG; // Joint 2

  /* Move the end effector to the desired x and y position */
  // Set Joint 1 (Servo 0) angle
  myservo[0].write(theta_1, servoSpeed, true); 

  // Set Joint 2 (Servo 1) angle
  myservo[1].write(calcServo1Angle(theta_2), servoSpeed, true); 
 
  // Wait
  delay(1000);
}

/* Activate the electric lifting magnet */
void activateMagnet() {  
  digitalWrite(magnetSignalPin, HIGH); // sets the digital pin ON  
}

/* Deactivate the electric lifting magnet */
void deactivateMagnet() {  
  digitalWrite(magnetSignalPin, LOW); // sets the digital pin OFF 
}

/* Move linear actuator down and then up */
void moveLinearActuator(int extension) {
  
  // goes from home position to extended position
  for (linearActuatorPos = linearActuatorHomePos; linearActuatorPos <= extension; linearActuatorPos += 1) { 
    linearActuator.write(linearActuatorPos); 
    delay(linearActuatorDelay);                       // wait for the actuator to reach the position
  }
  
  // goes from extended position to home position
  for (linearActuatorPos = extension; linearActuatorPos >= linearActuatorHomePos; linearActuatorPos -= 1) { 
    linearActuator.write(linearActuatorPos);          
    delay(linearActuatorDelay * 2);                          // wait for the actuator to reach the position
  }  
}

/* Pick up an object from one location, and place it in another */
void pickAndPlace(double xPosPick, double yPosPick, double xPosPlace, double yPosPlace) {
  
  // Move arm to the pick location
  moveArm(xPosPick, yPosPick);

  activateMagnet();

  // Pick up the object
  moveLinearActuator(180);

  // Move arm to the place location
  moveArm(xPosPlace, yPosPlace);

  deactivateMagnet();

  // Place the object (tweak this input here until you get desired results)
  moveLinearActuator(120);

  delay(1000); 
}

/* Return to the 0 degree home position */
void returnHome() {
  
  // Set servo positions to home position
  myservo[0].write(0, servoSpeed, true);  
  myservo[1].write(calcServo1Angle(0), servoSpeed, true);
}

2020-10-08-215918-1
2020-10-09-194559

Future Challenge Project: Add Computer Vision to Automate Pick and Place

scara-robot-and-vision
Image Source: Borangiu, Theodor & Anton, Florin & Anton, Silvia. (2015). Open Architecture for Vision-Based Robot Motion Planning and Control. Mechanisms and Machine Science. 29. 63-89. 10.1007/978-3-319-14705-5_3.

Up until now, we have placed an object at a predetermined location, and we hardcoded that location in our Arduino code. If you’re feeling really ambitious, what you can now do is integrate the Raspberry Pi camera so you can determine the object’s location automatically. 

What you’ll want to do is:

  • Turn on the Raspberry Pi camera.
  • Place a hex nut on the board, somewhere where the camera can see it, and the robotic arm can reach it.
  • Determine the coordinates of the object using the Raspberry Pi camera. This is the target location.
  • Send the coordinates of that object (in the robot’s base frame) from Raspberry Pi to Arduino.
  • Move the end effector to the target location.
  • Activate the electric lifting magnet.
  • Lower the linear actuator.
  • Pick up the hex nut.
  • Raise the linear actuator.
  • Move the linear actuator to the toy trash can.
  • Lower the linear actuator.
  • Deactivate the electric lifting magnet.
  • Place the hex nut.
  • Raise the linear actuator.
  • Return to the home position
  • Pick and place complete!

You will need to tweak the code in this tutorial to get everything working.

That’s it for today. Keep building!

Disclosure (#ad): As an Amazon Associate, I earn from qualifying purchases.

PID Control Made Simple

In this tutorial, I’ll explain how PID (Proportional-Integral-Derivative) Control works using an analogy.

Imagine we are the captain of a ship. We want the boat to maintain a heading of due north automatically, without any human intervention.

compass_direction_magnetic_compass

We go out and hire a smart robotics software engineer to write a control algorithm for the ship. 

The variable that we want to control is the ship’s heading, and we want to make sure the heading maintains a “set point” of due north (e.g. 0 degrees).

Proportional Control

  • If the ship is heading slightly off course to the left, we want the ship to steer slightly to the right.
  • If the ship is heading slightly off course to the right, we want the ship to steer slightly to the left.
  • If the ship is heading strongly off course to the left, we want the ship to steer strongly to the right.
  • If the ship is heading strongly off course to the right, we want the ship to steer strongly to the left.

In short, the steering magnitude is directly proportional to the difference between the desired heading and the current heading. The further you are off course, the harder the ship steers.

Mathematically, proportional control is: 

Control Output  = Kp * (Desired – Actual)

Where:

  • Control Output is what you want to control (e.g. steering intensity, speed, etc.)
  • Kp is some non-negative constant
  • Desired = Set Point (e.g. the heading you want to achieve…i.e. 0 degrees north)
  • Actual = Process Variable (e.g. the heading you measured)
  • Error = Desired – Actual

The Proportional term is all about adjusting the output based on the present error.

Integral Control

Now let’s suppose that there is a crosswind. Even though the ship is adjusting the steering in proportion to the heading error, there are still differences between the actual and desired heading that are accumulating over time as a result of this ongoing crosswind. 

The ship continues to drift off course even though proportional control is being applied.

The integral term looks for the residual error that is generated even after proportional control is applied. In this example, the residual error is caused by the wind, and it keeps adding up over time. The integral term seeks to get rid of this residual error by incorporating the historical cumulative value of the error. As the error decreases, the integral term will decrease.

Integral control looks for factors that keep pushing the ship off course and adjusts accordingly.

Mathematically, we now have to add the Integral term.

Control Output  = Kp * Error + Ki * Sum of Errors Over Time

The Integral term is all about adjusting the output based on the past error.

Derivative Control

Let’s suppose that the ship is steering hard to the left in order to correct the heading. You don’t want the ship to steer so hard that momentum causes the ship to overshoot your desired heading. 

What you want to do is have the ship slow down the steering as it approaches the heading. 

The derivative term of PID control does this. It is used to slow down the heading correction as the measured heading approaches the desired heading. This derivative term helps the ship avoid overshooting.

Mathematically, we now have to add the Derivative term to get the final PID Control equation:

Control Output  = Kp * Error + Ki * Sum of Errors Over Time + Kd * Rate of Change of the Error with Respect to Time

1-pid-control
How all of the PID control constants combine to generate the desired control response

The Derivative term is all about adjusting the output based on the future (predicted) error. If the error is decreasing too quickly with respect to time, this term will reduce the control output.

Summary

PID is a control method that is made up of three terms:

  1. Proportional gain that scales the control output based on the difference between the actual state of the system and the desired state of the system (i.e. the error).
  2. Integral gain that scales the control output based on the accumulated error.
  3. Derivative gain that scales the control output based on the rate of change of the error (i.e. how fast the error is changing).

How to Determine What Torque You Need for Your Servo Motors

In this tutorial, I will show you how to calculate how much torque you need for the servo motors (i.e. joints) on a robotic arm you are trying to build. 

Why is torque so important? When you want to build a robotic arm to perform some task in the world, you have to make sure that each joint of the arm (i.e. servo motor) is strong enough to lift whatever you want it to lift. In robotics jargon, the maximum weight that a robotic arm can lift is referred to as the maximum payload

This six degree of freedom robotic arm we built here can lift a pair of sunglasses, but the servos don’t have enough torque to lift a car, for example.

What is Torque?

Consider this wooden rod below.

2-torque-servo-motorsJPG

Let’s label its center of mass with a light blue circle. Imagine this blue circle is a nail that we have hammered into the wooden rod and a wall.

3-torque-servo-motorsJPG

If we apply a force F on the end of the rod at a distance r from the center of mass, what do you think will happen? 

Note that we are only concerned about the component of the force that is perpendicular to the position vector. The position vector is drawn from the axis of rotation (i.e. the blue nail) to the force vector (in blue below). The position vector must be perpendicular to the force vector.

4-torque-servo-motorsJPG

The rod will rotate in a counterclockwise direction around the axis.

5-torque-servo-motorsJPG

This force that is applied at a position r from the axis of rotation (which is directly out of the page) is known as torque. Torque is often represented by the Greek letter τ. The equation for torque is:

τ = r F 

It is worth repeating, but with torque we are only concerned about the component of the force that is perpendicular to the position vector. Any force component that is parallel to the position vector doesn’t generate torque.

For example, imagine we applied force to the end of the rod at an angle like this:

6-torque-servo-motorsJPG

The torque in this case just takes into account that red line above. Here, the equation for the torque is:

sin(θ) = Fperpendicular / F       … using trigonometry

Fsin(θ) = Fperpendicular               

Therefore,

τ = r F sin(θ)

The official metric (SI) units of torque is the Newton-meter (Nm). However in datasheets for servo motors, you’ll often see ounce-force-inch (oz-in) or kilogram-force centimeter (kg-cm).

In the real world, a servo motor’s axis is the blue nail. This is the robotic arm’s joint. The orange bar is the link of a robotic arm. The force F is the force acting on an object (that the robotic arm is trying to lift) due to gravity. 

7-torque-servo-motorsJPG

F = mass *  g

Where m is the mass the servo motor has to lift, and g is the acceleration due to gravity (9.80665 m/s2). 

The torque for this setup above is:

τ = m * g * r

Example 1

If you see a servo with a torque of 35kg-cm, what does that mean?

8-torque-servo-motorsJPG

Typically, when you see a value like 35 kg printed on a servo motor, what they are referring to is the stall torque, which, in this case, is 35 kg-cm. Stall torque is the torque load that causes a servo motor to “stall” or stop rotating.

A stall torque of 35 kg-cm means that the servo motor will stop rotating when it is trying to move a 35 kg weight at a radial distance of 1.0 cm. 

In the example below, we will assume the orange link has a mass of 0 kg.

9-torque-servo-motorsJPG

In case you’re wondering, what the force F is:

F = m * g = 35 kg * 9.80665 m/s2

F = 35 kg * 9.80665 m/s2

F = 343.2 N

Where N stands for newtons. Note that 1 N = 9.80665 kg.

Example 2

Let’s say the servo of the robotic arm rotates a bit, counterclockwise.

What is the torque in this case?

10-torque-servo-motorsJPG

τ = r F 

τ = (1.0 cm * cos(45°)) * (343.2 N)

τ = (.01 m * cos(45°)) * (343.2 N)

τ = (.00707m) * (343.2 N)

τ = 2.427 Nm

1 Nm is equal to 10.197162129779 kg-cm.

Therefore,

τ = 24.75 kg-cm

So, you can see that when the arm is extended out parallel to the ground surface, the torque is higher than when the arm is bent. 

This makes a lot of sense. Imagine holding your arm stretched out horizontally and trying to hold a bucket of water in place while trying not to bend your elbow. It would be pretty difficult!

Accounting for the Force of Gravity

In the example above, we have accounted for the force of gravity when calculating our torque requirements. However, we assumed that the links have no weight. In reality they do. 

Consider this diagram of a robotic arm below. It has four servo motors and a gripper on the end (at right). Each servo motor (i.e. joint) is connected by a link (typically a metal piece like you see in this six degree of freedom robotic arm here).

11-robotic-armJPG

To calculate the torque requirement, we start at the end effector (i.e. gripper) of the robotic arm and then work our way to the base of the robot. We need to account for all the pieces of the robot that are impacted by gravity:

  • Weight of the link
  • Weight of the joint
  • Weight of the object being lifted (e.g. the box below)
12-robotic-armJPG

Let’s start with joint 4. Joint 4 has to be strong enough to lift the box as well as link 4. 

Box:

  • The center of mass of the box is located at a distance r4 from the axis of rotation of joint 4.
  • The force of gravity acting on the box is equal to mbox * g. (where m means mass).
  • The torque due to the box is therefore r4 * mbox * g.

Link 4:

13-robotic-armJPG
  • The center of mass of the link is that red dot above. It is located at a distance r4/2  from the axis of rotation of joint 4.
  • The force of gravity acting on link 4 is equal to mlink4 * g (note that the product of mass and the gravitational acceleration constant is also known as the “weight”).
  • The torque due to the box is therefore (1/2) * r4 *  mlink4 * g.

Therefore:

Torque4 =  (r4 * mbox * g) + ((1/2) * r4 *  mlink4 * g)

Let’s now do one more. We’ll do joint 3. We place a red dot in the center of mass of link 3.

14-robotic-armJPG

Joint 3 has to be strong enough to lift the following components:

  • Box…………((r3 + r4) * mbox * g)
  • Link 4….…..((r3 + r4/2) * mlink4 * g)
  • Joint 4……..(r3 * mjoint4 * g)
  • Link 3………(r3/2 * mlink4 * g)

Therefore:

Torque3 =  ((r3 + r4) * mbox * g) + ((r3 + r4/2) * mlink4 * g) + (r3 * mjoint4 * g) + (r3/2 * mlink4 * g)

You keep doing this for the other joints.

Accounting for Angular Acceleration

The force of gravity on the links and payload (i.e. the box) is only part of the calculation of the torque requirement for a motor. We want our robotic arm to move and do useful work in the world…not just sit there with its arm stretched out, holding a box in place.

There is a torque required for a joint to move (i.e. generate angular acceleration) a link (or payload) from a rest position. Therefore, the total torque requirement for a servo is:

Torque Required By a Servo Motor = (Torque Due to Force of Gravity on Links and Payload) + (Torque Due to Angular Acceleration of Links and Payload)

This torque due to angular acceleration is calculated using the following equation:

τ = Iα

where I is the rotational inertia (or moment of inertia), and α is the angular acceleration around an axis. 

The value for I will vary depending on what is generating the angular acceleration (e.g. solid cylinder, thin rod, slab, etc.). Inertia is the “resistance an object has to any change in its velocity.” Therefore, rotational inertia in the case of a servo motor is the resistance the motor has to any change in its velocity. 

The units for rotational inertia are kg-m2. The unit for angular acceleration is rad/s2.

Example

Consider this joint below that is connected to a link. In this case, the motor will rotate counterclockwise in a direction that is at a 90 degree angle to the force of gravity (which is straight down). The only torque we have here is the torque required to generate angular acceleration.

τ = Iα

15-linkJPG

I in this case will be the sum of the rotational inertia of the motor and the link. 

I = Imotor + Ilink1

You can find the rotational inertia of the motor (Imotor) in the datasheet for the motor (do a Google search for the datasheet). The rotational inertia of the link (Ilink1) can be described as the rotational inertia of a rod of some length L and mass m, rotating about one end. The equation is as follows:

Ilink1=(1/3)*m*L2

16-linkJPG

α, the angular acceleration, will be the same for both the motor and the link since they are connected to each other. 

How do we find α?

Let’s assume that we want the motor to move 90° in 1.0 second and then stop (e.g. common in pick and place tasks). We can draw a graph of angular velocity ω (radians/second) vs. time t (seconds).

17-angular-velocityJPG

We want to minimize acceleration as much as possible so that we minimize the torque requirements for our servo motor. We could have any velocity curve we want, but the curve that minimizes acceleration is the one that increases linearly from rest, reaches a peak at the halfway point, and then decreases linearly from there.

The reason why this curve below gives the minimum acceleration is because acceleration is the slope of the velocity curve (i.e. change in angular velocity/change in time = angular acceleration). 

You can see that the magnitude of the slope is minimized on the black curve. The red and green curves get steep in some parts, which means the angular acceleration is high (and thus more torque is needed for the servo motor).

18-angular-velocityJPG

What is the required area underneath this curve below? The area of the curve (i.e. triangle) is equal to the distance the servo motor needs to move.

The formula for the area of a triangle (Atriangle) is: 

Atriangle = (1/2)*(base)*(height)

19-angular-velocityJPG

The distance the servo motor needs to move is 90°, which is equal to π/2 radians.

π/2 = (1/2)*(1.0)*(ωmax)

ωmax = π radians/second

Since α is the slope of the curve, we know that it is:

α = (change in y/ change in x) = (π/0.5) = 2π rad/s2

Now, we have all the numbers we need to calculate the required torque:

τ = (Imotor + (1/3)*m*L2) * (2π)

Let’s assume:

  • Imotor = 0 kg-m2 (we’ll assume the rotational inertia of the motor is negligible compared to the link, but you would typically get this value in the motor’s datasheet)
  • L = 0.75 m
  • m = 1.2 kg

τ = ((1/3)*(1.2kg)*(0.75 meters)2) * (2π rad/s2)

τ = 1.414  kg-m2/s2 = 1.414  Nm = 14.410 kg-cm = 200 oz-in

Now, that we’ve identified the torque requirements for the motor in motion (we covered the stationary motor case in the previous section of this post), we need to make sure we select a motor that will be able to exert 14.410 kg-cm of torque at all of the speeds in the curve below.

20-angular-velocityJPG

So the next step is to take a motor that has a stall torque greater than 14.410 kg-cm and plot the torque vs. speed curve. We need to make sure that both the maximum torque and maximum speed (i.e. ωmax) fall under this curve; otherwise, we could damage our motors.

Let’s suppose we searched around on the Internet at various electronics stores and found a motor with a no load speed of 45 RPM and a stall torque of 250 oz-in (18 kg-cm). Let’s draw the torque vs. speed curve. Note that the “no load speed” is the revolutions per minute of a motor when it is running at top speed with nothing attached to it.

21-stall-torqueJPG

From our analysis, we calculated that we need 200 oz-in of torque, so I’ll draw that on the graph as a blue line.

22-stall-torqueJPG

ωmax = π radians/second 

1 Radians Per Second =  9.5493 Revolutions Per Minute

ωmax = π radians/second * 9.5493 rpm/(radians/second) = 30 rpm 

Let’s draw that on the curve.

23-no-loadJPG

It looks like that pink dot is above the curve, so we might need a stronger motor. Let’s double check to see if that point is, in fact, above our torque vs. speed curve.

24-torqueJPG

Torque = (-250/45)*(30) + 250 = 83 oz-in

25-torqueJPG

We see that the motor generates 83 oz-in of torque when the speed is 30rpm. However, we need to have 200 oz-in of torque, so this motor is not strong enough for our project.

Now, let’s see if we found a motor with the following specifications. 

  • No-load speed = 100 rpm
  • Stall Torque = 350 oz-in

Do this work for our purposes? Let’s do the math.

Torque = (-350/100)*(30) + 350 = 245 oz-in

Since 245 > 200, this motor works for our purposes.

However, in our analysis we have not taken into account the rotational inertia of the motor, and we have assumed that there is no payload attached to the link. So, in a real-world use case, we need to account for those by incorporating them into our original calculation of I (i.e. the rotational inertia).

Accounting for Angular Acceleration and the Force of Gravity

Now let’s look at an example where we need to take both angular acceleration and the force of gravity into account in order to calculate the torque requirement.

We will reposition the joint-link combination we worked with in the previous section so that the body of the motor is now parallel to the surface. Here is how that looks:

26-gravityJPG

Here we have two torques:

  • Acceleration of the Link: τ = Iα
  • Gravity: τ = r F 

Adding the two torques we have:

τ = Iα + mass *  g * (r/2) * cos(θ)

Where r/2 is the distance from the axis of rotation to the center of mass of the link. The center of mass of the link is noted with a pink circle below.

27-mass-of-linkJPG

The mass of the link is 1.2 kg, and the link length is 0.75 meters. In the worst case, cos(θ) = 1. Therefore, the amount of torque that the motor needs to have the link overcome the downward force of gravity is:

mass *  g * (r/2) * cos(θ) = (1.2 kg)(9.8 m/s2)(0.75/2) = 4.41 Nm = 624 oz-in

You can see how the torque required to overcome the force of gravity is more than 3x the required torque to accelerate a link from rest (which we calculated as 200 oz-in).

Total torque required = 200 oz-in + 624 oz-in = 824 oz-in

Adding a Payload to the Robotic Arm

Now, let’s assume the robotic arm has something at the end of it that it needs to carry. We call this a payload.

28-payloadJPG

If you go to this list at Wikipedia, you will see that this object can be considered a “point mass”. The equation for rotational inertia for a point mass is:

I = Mr2

Where M = mass of the object, and r is the distance from the rotational axis to the center of mass of the object.

Earlier we found the torque required to produce angular acceleration for the link. That was:

τ = (Imotor + (1/3)*m*L2) * (2π)

τ = ((1/3)*(1.2kg)*(0.75 meters)2) * (2π rad/s2)

τ = 1.414  kg-m2/s2 = 1.414  Nm = 14.410 kg-cm = 200 oz-in

Now we need to add the rotational inertia of the object attached to the link. Let’s assume the object has a mass of 1.2kg (just like the mass of the link). The equation becomes:

τ = ((1/3)*(1.2kg)*(0.75 meters)2 + 1.2 kg * (0.75)2) * (2π rad/s2)

τ = 5.655  kg-m2/s2 = 5.655  Nm = 57.665 kg-cm = 800.8 oz-in

Now let’s go back here:

27-mass-of-linkJPG-1

We had:

τ = Iα + mass *  g * (r/2) * cos(θ)

τ = Iα + 4.41 Nm

We also have to add the torque of the payload due to gravity.

τ = Iα + 4.41 Nm + (1.2 kg)(9.8 m/s2)(0.75) 

τ = Iα + 4.41 Nm + 8.82 Nm

τ = Iα + 13.23 Nm

τ = Iα + 1873.5 oz-in

Therefore,

τ = Total amount of torque required to move the link and payload

  = (torque needed for angular acceleration) + (torque to overcome gravity) 

  = 800.8 oz-in + 1873.5 oz-in

  = 2674.3 oz-in

You now have the fundamentals to expand this calculation to multi-link robotic arms. That’s it for now. Keep building!

References

  • Here is a handy calculator that helps you select the appropriate servo motor for each joint of your robotic arm.
  • Khan Academy has a good comprehensive short course on torque.
  • Professor Angela Sodemann has a great tutorial on her site RoboGrok.com that covers torque requirements for manipulators