Gesture-controlled robot arm.

usman
15 min readFeb 9, 2023

--

Hello everyone! It’s been a while since my last post and I’m excited to share with you a project I worked on some time ago. I’ll be showing you how I built a robot arm and controlled it using hand gestures and computer vision. Here’s a demo video of the arm in action during its development phase to give you a glimpse of what I’ve created.

A demo video showing the arm in development

The process starts with a camera capturing my hand and its landmarks, as seen in the image. By tracking specific landmarks, such as the tip of the thumb and index fingers, the relative movement of these landmarks can be determined and translated into the movement of servos. This is done through a Python script that processes the data and sends integer values to an Arduino, which controls the servo motors.

The operational flow goes from

Camera —> python script —> Arduino —> servo motors

Hand landmarks

Here’s a list of items I used for this project:

  1. Robot arm kit (frame and servo motors (MG996) only)
  2. Arduino board (plus USB cable)
  3. Jumper wires
  4. Phone charger
  5. PCA9685 servo motor driver
  6. Laptop
  7. Suction pump kit
  8. A relay module

Programming environments used:

  1. Arduino IDE
  2. PyCharm editor

Prerequisites:

  • Knowledge of OpenCV (tutorial available on youtube)
  • Knowledge of C++ and Python

I needed to modify the robot arm assembly (for the kit I bought) due to the servo motors not being able to move the arm when fully assembled, resulting in a loss of some degrees of freedom (DOF) and the removal of a gripper as the end effector. I opted to use a suction pump mechanism instead. For this project, you can purchase only the robot arm kit I used or you buy only the chassis and upgrade to more powerful servos to work with the complete assembly. The latter option would require you to use this article as a guide and make modifications to achieve your desired results.

I also had to change some of the servo motor gears to metal ones. I recommend you get more powerful servos.

  1. Assemble the robot arm:
  • Load the Arduino code onto the board and connect the servo motors using the circuit diagram.
  • It’s time to assemble the robot arm. Before starting, make sure to load the Arduino code by downloading it and installing the HCPCA9685 library as described here. Connect the servo motors using the provided circuit diagram to ensure they are in the desired position. Start by connecting the servo at the base of the arm (rotating base joint) to pin 0 of the PCA9865, followed by the next servo in the arm (shoulder joint)connected to pin 3, and so on, moving from left to right of the PCA9685. Finally, power up the Arduino board and wait for the servo motors to reach their positions.

2. Arm joints

  • Place pulleys on the servo motors and attach screws.
  • Now it’s time to assemble the other parts of the robot arm. Use the video linked here as a guide, but feel free to use your own approach to achieve the pose depicted in the image. If you encounter any issues during testing, such as a joint not moving, check the servo motor for heat. If it’s hot, there may be an assembly problem at that joint preventing it from functioning properly.
Pictures showing the robot arm in its home position.
Additional pictures for reference when assembling the arm

3. Connect the suction pump:

  • Connect the hose as shown in the diagram below, the black arrows represent the connection and flow of air.
Suction pump mechanism
  • Connect the negative terminals of the vacuum pump, relay module, and solenoid valve to the negative terminal of the power supply.
  • Connect the positive terminal of the relay module to the positive terminal of the power supply.
  • Connect the signal wire of the relay module to digital pin 3 of the Arduino board.
  • Connect the positive terminal of the vacuum pump to the normally open (NO) terminal of the relay module.
  • Connect the positive terminal of the solenoid valve to the normally closed (NC) terminal of the relay module.
  • Connect the relay module’s common terminal to the power input’s positive terminal.

4. Arduino code:

  • Set up and initialize libraries and variables.
#include <Servo.h>

#include <Wire.h>
#include <Adafruit_PWMServoDriver.h>

// called this way, it uses the default address 0x40
Adafruit_PWMServoDriver pwm = Adafruit_PWMServoDriver();


#define USMIN 1000//600 // This is the rounded 'minimum' microsecond length based on the minimum pulse of 150
#define USMAX 2000//2400 // This is the rounded 'maximum' microsecond length based on the maximum pulse of 600
#define SERVO_FREQ 50 // Analog servos run at ~50 Hz updates

uint16_t Pos1;
uint16_t Pos2;
uint16_t Pos3;
uint16_t Pos0;
int ang;
int ang2;
int ang3;
int ang0;
int X; //variable storing data from the index finger (landmark 8)
int Y; //variable storing data from the middle finger(landmark 12)
int Z; //variable storing data from the ring finger (landmark 16)
int J; //variable storing data from the bottom of the palm (landmark 0)
int K; //variable storing data from the thumb finger (landmark )
int L; //variable storing data from the thumb finger (landmark )
const int RELAY_PIN = 3; // auction pump relay pin
const int RELAY_PIN = 3;

  • The ‘setup’ section runs once after powering up and positions the servo motors.
void setup() {
Serial.begin(9600);
Serial.println("Ready"); // prints ready on the serial port
pinMode(RELAY_PIN, OUTPUT); //setting relay pin to output
digitalWrite(RELAY_PIN, LOW); //putting off relay pin
Pos1 = 1500;
Pos2 = 1500;
Pos3 = 1500;
Pos0 = 1500;
pwm.begin();

pwm.setOscillatorFrequency(27000000);
pwm.setPWMFreq(SERVO_FREQ); // Analog servos run at ~50 Hz updates

for(int i = 0; i < 4; i++) { // loop to position the servo motors in their initial state after startup

pwm.writeMicroseconds(i, Pos1);
delay(10);

}
}
  • The crucial component is the “postn” function, which converts variables set in the “loop” function into motion. It takes four inputs (A, B, C, and D)
  • A is the point on the palm being tracked to control a servo motor and is sent serially from the computer to the Arduino and read by the “loop” function.
  • The function verifies that the servo’s current position is within its minimum and maximum limits before making adjustments in increments of 20 in either direction depending on the trigger it goes past. Triggers B and C are displayed on the screen when running the code at landmark 0 (wrist/lower palm).
  • B and C are the upper/leftward and lower/rightward triggers that control the servo movement up/right or down/left respectively when the tracked palm point crosses them.
  • The last part of the “‘postn’’ function turns the suction pump on and off based on the position of hand landmarks 3 and 4.
void Postn()
{

if ((X < 90) && (Pos1 > USMIN) && (Pos1 < USMAX)) // if the tracked landmark (stored as X) is lower than the lower trigger (90) and
{ // and the current position (pos1) of the servo is greater than its minimum limit (usmin)
Pos1 -= 20; //and the current position of the servo is less than its maximum limit (usmax)
pwm.writeMicroseconds(1, Pos1); // the servo position moves in steps of 20
Serial.print("X = "); // a signal is sent to the servo to effect the change in position (pos1)
Serial.println(Pos1);
if (Pos1 == USMIN) // if the variable storing the position of the servo gets to the min limit (servomax)
{Pos1 = USMIN + 20;} // the servo will get stuck; hence, this line reduces its value at the end of this section of the code. you can comment this line and run a test to better understand
}

if ((X > 150) && (Pos1 > USMIN) && (Pos1 < USMAX)) // if the tracked landmark (stored as X) is higher than the uppwer trigger (150) and
{ // and the current position (pos1) of the servo is greater than its minimum limit (usmin)
Pos1 += 20; //and the current position of the servo is less than its maximum limit (usmax)
pwm.writeMicroseconds(1, Pos1); // a signal is sent to the servo to effect the change in position (pos1)
Serial.print("X = ");
Serial.println(Pos1);
if (Pos1 == USMAX) // if the variable storing the position of the servo gets to the max limit (servomax)
{Pos1 = USMAX - 20;} // the servo will get stuck; hence, this line reduces its value at the end of this section of the code. you can comment this line and run a test to better understand
}

if ((Y < 70) && (Pos2 > USMIN) && (Pos2 < USMAX)) // the logic above applies to the here and for the lest of this function
{
Pos2 -= 20;
pwm.writeMicroseconds(2, Pos2);
Serial.print("Y = ");
Serial.println(Pos2);
if (Pos2 == USMIN)
{Pos2 = USMIN + 20;}
}

if ((Y > 130) && (Pos2 > USMIN) && (Pos2 < USMAX))
{
Pos2 += 20;
pwm.writeMicroseconds(2, Pos2);
Serial.print("Y = ");
Serial.println(Pos2);
if (Pos2 == USMAX)
{Pos2 = USMAX - 20;}
}

if ((Z < 70) && (Pos3 > USMIN) && (Pos3 < USMAX))
{
Pos3 += 20;
pwm.writeMicroseconds(3, Pos3);
Serial.print("Z = ");
Serial.println(Pos3);
if (Pos3 == USMAX)
{Pos3 = USMAX - 20;}
}

if ((Z > 130) && (Pos3 > USMIN) && (Pos3 < USMAX))
{
Pos3 -= 20;
pwm.writeMicroseconds(3, Pos3);
Serial.print("Z = ");
Serial.println(Pos3);
if (Pos3 == USMIN)
{Pos3 = USMIN + 20;}
}

if ((J < 220) && (Pos0 > USMIN) && (Pos0 < USMAX))
{
Pos0 += 20;
pwm.writeMicroseconds(0, Pos0);
Serial.print("J = ");
Serial.println(Pos0);
if (Pos0 == USMAX)
{Pos0 = USMAX - 20;}
}

if ((J > 370) && (Pos0 > USMIN) && (Pos0 < USMAX))
{
Pos0 -= 20;
pwm.writeMicroseconds(0, Pos0);
Serial.print("J = ");
Serial.println(Pos0);
if (Pos0 == USMIN)
{Pos0 = USMIN + 20;}
}

if (K > L) //The pump function checks if hand landmark 4 (tip of thumb) is to the right or left side
{ //of hand landmark 3 (IP joint), this in turn switches on and off the suction pump.
digitalWrite(RELAY_PIN, LOW);
Serial.print("K =");
Serial.println(K);
Serial.print("L =");
Serial.println(L);

}

if (K < L)
{
digitalWrite(RELAY_PIN, HIGH);
Serial.print("K");
Serial.println(K);
Serial.print("L");
Serial.println(L);
}

}
  • The ‘loop’ function checks the serial port for data transmitted from the computer and calls the ‘postn’ function accordingly.
void loop() {//   The 'loop' function checks the serial port for data being transmitted 
//from the computer; depending on the data it gets, it calls upon the 'postn' function.
// or the pump function

if(Serial.available() > 0)
{
if(Serial.read() == 'X')
{
X = Serial.parseInt();
if(Serial.read() == 'Y')
{
Y = Serial.parseInt();
if(Serial.read() == 'Z')
{
Z = Serial.parseInt();
if(Serial.read() == 'J')
{
J = Serial.parseInt();
if(Serial.read() == 'K')
{
K = Serial.parseInt();
if(Serial.read() == 'L')
{
L = Serial.parseInt();
Postn();
}
}
}
}
}
}
}


}
  1. The comments in the python script explain all you need to know about it. Open the python script with PyCharm and run the script. A new window pops up showing what the camera sees, place your hands properly and move the appropriate landmarks to get the robot arm moving. You can open the serial monitor on the Arduino IDE to see the data that is transmitted to the Arduino but ensure to close the serial monitor whenever you want to restart the python script to prevent errors.
import cv2    #import neccesary libraries after adding them as packages to this project
import mediapipe as mp # go to settings > python interpreter
import serial
import time
import math

Arduino=serial.Serial('/dev/cu.usbmodem14101', 9600, timeout=0.1) #initialize the serial port(in quotation marks) for communicatin with the arduino

wCam, hCam = 1240, 720 # variable for setting the camera window width and height
cam = cv2.VideoCapture(0) # start the webcam, use 0 for and inbuilt camera and 1 for an external one
cam.set(3, wCam) #setting the camera window width and height
cam.set(4, hCam)
smoothV = 2
pVal = 0
cVal = 0

color = (255, 255, 255)

class mpHands: #class used to detect hands, hand landmarks, measure distance and angle between hand landmarks
# watche this video for an explanation of the class; https://www.youtube.com/watch?v=WQeoO7MI0Bs&t=8774s
def __init__(self, mode=False, modelComplexity=1, maxHands=2, TrackCon=0.5, DetectCon=0.5):
self.mode = mode
self.modelComplexity = modelComplexity
self.maxHands = maxHands
self.TrackCon = TrackCon
self.DetCon = DetectCon

self.mpHands = mp.solutions.hands
self.hands = self.mpHands.Hands(self.mode, self.maxHands, self.modelComplexity,
self.TrackCon, self.DetCon)
self.mpDraw = mp.solutions.drawing_utils
def Marks(self,frame):
myHands=[]
handsType=[]
frameRGB=cv2.cvtColor(frame,cv2.COLOR_BGR2RGB)
results=self.hands.process(frameRGB)
if results.multi_hand_landmarks != None:
for hand in results.multi_handedness:
#print(hand)
#print(hand.classification)
#print(hand.classification[0])
handType=hand.classification[0].label
handsType.append(handType)
for handLandMarks in results.multi_hand_landmarks:
myHand=[]
for landMark in handLandMarks.landmark:
h, w, c = frame.shape
myHand.append((int(landMark.x*w),int(landMark.y*h)))
myHands.append(myHand)
return myHands, handsType

def findDistance(self, a, b, frame ):
x1, y1 =a[0], a[1]
x2, y2 =b[0], b[1]
cx, cy = (x1 + x2) // 2, (y1 + y2) // 2 # center point between thumb and index finger

cv2.circle(frame, (x1, y1), 5, (255, 255, 255), cv2.FILLED) # circle on thumb
cv2.circle(frame, (x2, y2), 5, (255, 255, 255), cv2.FILLED) # circle on index finger
cv2.circle(frame, (cx, cy), 5, (255, 255, 255), cv2.FILLED) # circle at center point bte thumb and index

cv2.line(frame, (x1, y1), (x2, y2), (255, 255, 255), 3) # line btw index and center point


length = int(math.hypot(x2 - x1, y2 - y1))
# print(length)
return length, frame, [x1, y1, x2, y2, cx, cy]

def findAngle(self, a, b, c, frame ):
#get the landmarks
x1, y1 = hand[a]
x2, y2 = hand[b]
x3, y3 = hand[c]
#get the angle
angle = math.degrees(math.atan2(y3-y2, x3-x2) - math.atan2(y1-y2, x1-x2))
if angle<0:
angle= angle+360
return angle
#print(angle)

width=1280
height=720
findHands=mpHands(2)

while True:
ignore, frames = cam.read()
frame= cv2.flip(frames, 1) #fliping the camera output sideways, comment this line to see the difference
handData, handType = findHands.Marks(frame)

for hand, handType in zip(handData, handType):
right = 0
left = 0
if handType == 'Right':
handColor = (0, 0, 255)

#tracking landmark 0 located at the wrist (lower part of the palm)
l1, l2 = hand[0] # x and y coordinates for the point at the bottom of the palm (wrist)
cv2.circle(frame, (l1, l2), 10, (0, 0, 255), cv2.FILLED) # draw a red circle at the point
# this point controlls the rotation of the base of the arm
cv2.line(frame, (50, l2), (220, l2), (46, 98, 84), 3) #this lines draw a green, white and green line on the screen
cv2.line(frame, (220, l2), (370, l2), (255, 255, 255), 3) #movement of landmark 0 to the green part of the line makes the arm
cv2.line(frame, (370, l2), (550, l2), (46, 98, 84), 3) # rotate to the the left or right (when it crosses the limits triggers at the upper and lower points of the line (220 and 370 on the x axis respectively)

cv2.circle(frame, (50, l2), 5, (255, 255, 255), cv2.FILLED) #these lines draw a circle at the two ends of the gree, white and green line
cv2.circle(frame, (550,l2), 5, (255, 255, 255), cv2.FILLED) # they also draw circles at the two boundaries between the green and white line
cv2.circle(frame, (220, l2), 5, (255, 255, 255), cv2.FILLED)
cv2.circle(frame, (370, l2), 5, (255, 255, 255), cv2.FILLED)

cv2.putText(frame, 'A', (l1,l2-50), cv2.FONT_HERSHEY_SIMPLEX, # A is shown on the landmark being tracked
0.5, color, 2)
cv2.putText(frame, 'B', (220, l2+50), cv2.FONT_HERSHEY_SIMPLEX,0.5, color, 2) # prints B at the location of the leftward triggers
cv2.putText(frame, 'c', (370, l2 + 50), cv2.FONT_HERSHEY_SIMPLEX, 0.5, color, 2) # prints B at the location of the rightward triggers
cv2.putText(frame, 'servo 0', (280, l2 + 50), cv2.FONT_HERSHEY_SIMPLEX, 0.5, color, 2) # prints the pin of servo being controlled

if (51 <= l1 <= 499): # the total length of the line created above is 448 (449-51) on the X axis
J = l1 # if the landmark being tracked is between the range above then it is stored with the variable J
elif (l1 < 51): # if the point being tracked (landmark 0) is at a position less than 51 on the X axis (the min point on the line drawn above
J = 51 #it is still stored as 51 because that is the lower limit and this being absent would result in errors when transferring data to the arduino( nothing will be sent to the arduino and the python script is coded such that something must be sent, thats why errors will come up)
elif (l1 > 499): # the same applies here with the upper limit of 499
J = 499

# tracking landmark 8 located at the tip of the index finger, this controlls the shoulder joint
l1, l2 = hand[8] # the same logic used to track landmark 0 applies here
cv2.circle(frame, (l1, l2), 10, (0, 0, 255), cv2.FILLED)

cv2.line(frame, (l1, 20), (l1, 90), (46, 98, 84), 3)
cv2.line(frame, (l1, 90), (l1, 150), (255, 255, 255), 3)
cv2.line(frame, (l1, 150), (l1, 220), (46, 98, 84), 3)

cv2.circle(frame, (l1, 20), 5, (255, 255, 255), cv2.FILLED)
cv2.circle(frame, (l1, 220), 5, (255, 255, 255), cv2.FILLED)
cv2.circle(frame, (l1, 90), 5, (255, 255, 255), cv2.FILLED)
cv2.circle(frame, (l1, 150), 5, (255, 255, 255), cv2.FILLED)
if (21 <= l2 <= 219):
X = l2
elif (l2 < 21):
X = 21
elif (l2 > 179):
X = 179

# tracking landmark 12 located at the tip of the middle finger, this controlls the elbow joint
l1, l2 = hand[12] # the same logic used to track landmark 0 applies here
cv2.circle(frame, (l1, l2), 10, (0, 0, 255), cv2.FILLED)

cv2.line(frame, (l1, 20), (l1, 70), (46, 98, 84), 3)
cv2.line(frame, (l1, 70), (l1, 130), (255, 255, 255), 3)
cv2.line(frame, (l1, 130), (l1, 180), (46, 98, 84), 3)

cv2.circle(frame, (l1, 20), 5, (255, 255, 255), cv2.FILLED)
cv2.circle(frame, (l1, 180), 5, (255, 255, 255), cv2.FILLED)
cv2.circle(frame, (l1, 70), 5, (255, 255, 255), cv2.FILLED)
cv2.circle(frame, (l1, 130), 5, (255, 255, 255), cv2.FILLED)
if (21 <= l2 <= 179):
Y = l2
elif (l2 < 21):
Y = 21
elif (l2 > 179):
Y = 179

# tracking landmark 16 located at the tip of the ring finger, this controlls the wrist joint
l1, l2 = hand[16] # the same logic used to track landmark 0 applies here
cv2.circle(frame, (l1, l2), 10, (0, 0, 255), cv2.FILLED)

cv2.line(frame, (l1, 20), (l1, 70), (46, 98, 84), 3)
cv2.line(frame, (l1, 70), (l1, 130), (255, 255, 255), 3)
cv2.line(frame, (l1, 130), (l1, 180), (46, 98, 84), 3)

cv2.circle(frame, (l1, 20), 5, (255, 255, 255), cv2.FILLED)
cv2.circle(frame, (l1, 180), 5, (255, 255, 255), cv2.FILLED)
cv2.circle(frame, (l1, 70), 5, (255, 255, 255), cv2.FILLED)
cv2.circle(frame, (l1, 130), 5, (255, 255, 255), cv2.FILLED)
if (21 <= l2 <= 179):
Z = l2
elif (l2 < 21):
Z = 21
elif (l2 > 179):
Z = 179


# this part id used to controll the suction pump. the suction pump is switched on or off depending on weather the tip of the thumb is positioned
# at he left or right of the joint below the tip of the thumb
l1, l2 = hand[4] #this represents the X and Y coordinated of tip of the thumb
l3, l4 = hand[3] #this represents the X and Y coordinated of joint below the tip of the thumb

cv2.circle(frame, (l1, l2), 10, color, cv2.FILLED) #this draws a circle at landmark 4, color was decleared in line 17

cv2.line(frame, (l3, l4+20), (l3, l4-100), (255, 255, 255), 3) #draws a white vertical line at landmark 3
#cv2.line(frame, (65, l2), (80, l2), (255, 0, 0), 3)

cv2.circle(frame, (l3, l4+20), 5, (255, 255, 255), cv2.FILLED) # draws circles at the two ends of the line drawn above
cv2.circle(frame, (l3, l4-100), 5, (255, 255, 255), cv2.FILLED)
#cv2.circle(frame, (80, l2), 5, (255, 255, 255), cv2.FILLED)
K = l1
L = l3
if ( l1 < l3): # the color of the circle at the tip of the thumb changes to red or green
color = (46, 98, 84) # depending on its position (to the right or left of the joint below the thumb (landmark 3))
elif (l1 > l3): # this signifies weather the pupmp is powered on or off
color = (0, 0, 255)


values = 'X{0}Y{1}Z{2}J{3}K{4}L{5}'.format(X, Y, Z, J, K, L) # all the variables used to store data are here
Arduino.write(values.encode('utf-8')) # the data containing the position of the landmarks being tracked are sent to the arduino

print(values) # the data being transferred is displayed




cv2.imshow('my WEBcam', frame)
#cv2.moveWindow('my WEBcam',0,0)
if cv2.waitKey(1) & 0xff ==ord('q'): # press the Q button on the keyboard to stop the camera
break
A demo video of the hand after completion

That would be all for now, you can always improve on this project better servo motors, and tweaking the code.Additionally, a depth vision camera can be embedded for more precise control of the arm by tracking the movement of an entire finger instead of a single landmark on the finger.

Your claps and comments are always appreciated.

You can get the Arduino and python codes on my GitHub repo.

--

--