Assignment:

Individual

- Design and produce something with a digital fabrication process  (incorporating computer-aided design and manufacturing) not covered in another assignment, documenting the requirements that your assignment meets, and including everything necessary to reproduce it.

 

 

Software :

-Arduino IDE

-Processing

 

Materials :

-Arduino Braccio robot arm

-Arduino USO

-Stepper shield

-HC-05 Bluetooth module

 

 

Accomplised

 

-Understood the working of stepper motors

-Understood the working of a 6 Axis robot arm

-Learned how to calibrate and control the arm

-Controlled the working of the arm with different methods

-Programmed the arm to respond to wireless and wired commands

 

 

 

Group Work

 

Download Files

Objective:

 

My aim for this week is to explore a little into the world of robotics as I am completely new to it. I have taken up robotic arm as my subject and this is what I intend to do:

 

-Study the working of the arm

-Control the arm by different methods.

 

Robot Arm:

 

A robotic arm is a type of mechanical arm, usually programmable, with similar functions to a human arm; the arm may be the sum total of the mechanism or may be part of a more complex robot. The links of such a manipulator are connected by joints allowing either rotational motion (such as in an articulated robot) or translational (linear) displacement. The links of the manipulator can be considered to form a kinematic chain. The terminus of the kinematic chain of the manipulator is called the end effector and it is analogous to the human hand.

The robot arm can be classified into how many directions it can move. That called Degrees of freedom

 

Degrees of Freedom (DOF)

 

The degrees of freedom, or DOF, is a very important term to understand. Each degree of freedom is a joint on the arm, a place where it can bend or rotate or translate. You can typically identify the number of degrees of freedom by the number of actuators on the robot arm.

Thanks to my instructor Rudrapal who was kind enough to lend me his Arduino Braccio robotic arm, to experiment this week. The Arduino braccio is a 6 axis robot arm.

https://store.arduino.cc/usa/tinkerkit-braccio

It is called as six degrees of freedom or six-axis robot because it is capable of rotating at six different axes. The following list specifies the functions of each axis.

 

Axis 1 – It is located at the base of a robot, and helps it to rotate from left to right.

Axis 2 – It helps the lower arm of a robot to move in an up and down motion.

Axis 3 – It allows the upper arm of a robot to move forward and backward.

Axis 4 – This axis is known as wrist roll, and it rotates the upper arm of a robot in a circular movement.

Axis 5 – It permits the wrist of the robot’s arm to raise and lower.

Axis 6 – It allows the wrist of the robot’s arm to rotate freely in a circular motion.

All the above six axes are controlled with the help of servo motors.

https://en.wikipedia.org/wiki/Robotic_arm

Servo Motor

 

The servo motor is usually a simple DC motor controlled for specific angular rotation with the help of additional servomechanism (a typical closed-loop feedback control system). Now day’s servo system has large industrial applications.

The main reason behind using a servo is that it provides angular precision, i.e. it will only rotate as much we want and then stop and wait for next signal to take further action. The servo motor is unlike a standard electric motor which starts turning as when we apply power to it, and the rotation continues until we switch off the power.

What's inside the servo?

 

To fully understand how the servo works, you need to take a look under the hood. Inside there is a pretty simple set-up: a small DC motor, potentiometer, and a control circuit. The motor is attached by gears to the control wheel. As the motor rotates, the potentiometer's resistance changes, so the control circuit can precisely regulate how much movement there is and in which direction.

 

When the shaft of the motor is at the desired position, the power supplied to the motor is stopped. If not, the motor is turned in the appropriate direction. The desired position is sent via electrical pulses through the signal wire. The motor's speed is proportional to the difference between its actual position and desired position. So if the motor is near the desired position, it will turn slowly, otherwise, it will turn fast. This is called proportional control. This means the motor will only run as hard as necessary to accomplish the task at hand, a very efficient little guy.

The above details explain what the robot arm is made of and by understand the principle and the placement of the servo motor, the arm can be controlled accordingly.

Arduino Braccio

 

 

Braccio is 6 axes robotic arm from Arduino itself. The package comes with all the plastic parts, motors, screws, and shield for Arduino UNO which has to be assembled. It also comes with a quick startup guide, and the following link is the pdf of the same.

https://store.arduino.cc/usa/tinkerkit-braccio

Quick Start-up Guide

https://docs-emea.rs-online.com/webdocs/14da/0900766b814da22f.pdf

There are several videos on Youtube explaining how to assemble the braccio. The following video is by Arduino and watching the video gives a clear idea how the machine is built.

Another major plus factor about Arduino Braccio is that it comes with a Braccio shield. So the shield just has to be placed on Arduino and then its good to go. This saves a lot of wired mess.

Braccio library has to be installed on Arduino to run the machine with the shield. The library for the same has to be found in the below link:

https://github.com/arduino-org/arduino-library-braccio

Calibrating the machine

 

When the arm is being assembled the servo motors are being placed in random positions. Its hard to know what the normal (i.e 0* position )of the motor. Hence once the arm with all its components is assembled calibrating it, should be the first task. There are several softwares to do so, but since I am using Arduino Braccio the start up guide comes with instructions and a code to calibrate it.

Code

#include <Braccio.h>

#include <Servo.h>

 

Servo base;

Servo shoulder;

Servo elbow;

Servo wrist_rot;

Servo wrist_ver;

Servo gripper;

 

void setup() {

}

 

void loop() {

 

  // the arm is aligned upwards  and the gripper is closed

                     //(step delay, M1, M2, M3, M4, M5, M6);

  Braccio.ServoMovement(20,         90, 90, 90, 90, 90,  73);

 

}

Once the calibration was done I ran a few examples codes to see the working of the machine. It was really amazing to watch the machine move and perform a task. I ran movement code and move the sponge code. The video for the same can be found below.:

Braccio Simple Movement

The main objective of this week is to control the arm in multiple ways. I chose to control with MPU6050 which has an accelerometer and Gyroscope

 

Accelerometer and Gyroscope

 

MPU 6050 is an IMU sensor. Inertial Measurement Units (IMUs) is a self-contained system that measures linear and angular motion usually with a triad of gyroscopes and triad of accelerometers. An IMU can either be gimballed or strapdown, outputting the integrating quantities of angular velocity and acceleration in the sensor/body frame. They are commonly referred to in the literature as the rate-integrating gyroscopes and accelerometers.

IMU sensors usually consist of two or more parts. Listing them by priority, they are the accelerometer, gyroscope, magnetometer, and altimeter. The MPU 6050 is a 6 DOF (degrees of freedom) or a six-axis IMU sensor, which means that it gives six values as output: three values from the accelerometer and three from the gyroscope. The MPU 6050 is a sensor based on MEMS (micro electro mechanical systems) technology. Both the accelerometer and the gyroscope are embedded inside a single chip. This chip uses I2C (inter-integrated circuit) protocol for communication.

 

How Does an Accelerometer Work?

 

An accelerometer works on the principle of the piezoelectric effect. Imagine a cuboidal box with a small ball inside it, like in the picture above. The walls of this box are made with piezoelectric crystals. Whenever you tilt the box, the ball is forced to move in the direction of the inclination due to gravity. The wall that the ball collides with creates tiny piezoelectric currents. There are three pairs of opposite walls in a cuboid. Each pair corresponds to an axis in 3D space: X, Y, and Z axes. Depending on the current produced from the piezoelectric walls, we can determine the direction of inclination and its magnitude.

 

How Does a Gyroscope Work?

Gyroscopes work on the principle of Coriolis acceleration. Imagine that there is a fork-like structure that is in a constant back-and-forth motion. It is held in place using piezoelectric crystals. Whenever you try to tilt this arrangement, the crystals experience a force in the direction of inclination. This is caused as a result of the inertia of the moving fork. The crystals thus produce a current in consensus with the piezoelectric effect, and this current is amplified. The values are then refined by the host microcontroller. Check this short video that explains how a MEMS gyroscope works.

 

The Following is the pinout configuration to connect MPU6050 to Arduino.

Gyroscopes work on the principle of Coriolis acceleration. Imagine that there is a fork-like structure that is in a constant back-and-forth motion. It is held in place using piezoelectric crystals. Whenever you try to tilt this arrangement, the crystals experience a force in the direction of inclination. This is caused as a result of the inertia of the moving fork. The crystals thus produce a current in consensus with the piezoelectric effect, and this current is amplified. The values are then refined by the host microcontroller. Check this short video that explains how a MEMS gyroscope works.

 

The Following is the pinout configuration to connect MPU6050 to Arduino.

Testing the MPU6050 with Processing

 

This test is to check the movement of the sensor in MPU6050. To watch the graphical interface of the movement we have to use Processing. Processing can be downloaded from here.

https://processing.org/

There certain libraries for Arduino and Processing that needs to be downloaded before we begin.

 

For Arduino:

https://github.com/jrowberg/i2cdevlib

Installing

For Processing;

http://toxiclibs.org/downloads/

Installing

Programming

 

First, we have to use Arduino to program the MPU6050 and then processing to look at the GUI. Once the MPU6050 libraries are loaded there will be an example program called MPU6050_DMP6. It can be found in:

 

--> Examples. Next, open the example program from File --> Examples --> MPU6050 --> Examples --> MPU6050_DMP6.

MPU6050 DMP6

Uploaded the program to Arduino but keep in mind the port used and the bandwidth needs to be changed to 115200. Once the program is uploaded open up the serial monitor, and you would be asked to enter any character.

Serial Monitor

The monitor will satrt displaying values form the sensor.

 

Now moving on to Processing. MPUteapot is a program that needs to be used for this process. The program can be downloaded from here

MPU Teapot test

Once the program is opened and the libraries are in place certain values need to be edited.

Change Values

 The values of the com port and bandwidth needs to be edited as per the settings in Arduino. Once the values are edited, hit Run. The following video is the result of my experimentation with MPU6050

MPU Teapot Test

 The values of the com port and bandwidth needs to be edited as per the settings in Arduino. Once the values are edited, hit Run. The following video is the result of my experimentation with MPU6050

Programming the Braccio

 

Now as I said earlier Braccio comes with certain libraries and coding for the same is very different.

Code Explanation

The following is the calibration code and as shown the value 20 refers to the speed of the arm movement and then the following values are the angles of the servo. In this case, everything is 90 except the last as it is the gripper value.

 

This is different as post to the usual Arduino code as we would usually define the servo and have to write the servo. This language of the programming had to be followed when the braccio shield is used. The challenge is to modify the code that would suit our needs.

 

I found an example code from the following youtube video.

https://www.youtube.com/watch?v=8wvEauCCvio

The attempt is to control 3 servos with mpu6050. I used the same code but modified the code to suit the braccio shield.

Code

#include <Braccio.h>

#include <Wire.h>

#include <I2Cdev.h>

#include <MPU6050.h>

#include <Servo.h>

 

Servo base;

Servo shoulder;

Servo elbow;

Servo wrist_rot;

Servo wrist_ver;

Servo gripper;

MPU6050 accelgyro;

 

int16_t ax, ay, az;

int16_t gx, gy, gz;

 

double accXangle;

double accYangle;

double accZangle;

 

double gyroXangle = 180;

double gyroYangle = 180;

double gyroZangle = 180;

 

uint32_t timer;

void setup() {

 

  Braccio.begin();

  Wire.begin();

 

  Serial.begin(38400);

 

  Serial.println("initiate I2C");

 

  accelgyro.initialize();

 

  Serial.println("Testing Connection");

  Serial.println(accelgyro.testConnection() ? "MPU6050 Connected Successfully" : "Connection Unsuccessful");

  timer = micros();

}

 

void loop() {

 

  accelgyro.getMotion6(&ax, &ay, &az, &gx, &gy, &gz);

 

  accXangle = (atan2(ax,az) + PI) * RAD_TO_DEG;

  accYangle = (atan2(ay,az) + PI) * RAD_TO_DEG;

  accZangle = (atan2(ax,ay) + PI) * RAD_TO_DEG;

 

  double gyroXrate = ((double)gx / 20.0);

  double gyroYrate = -((double)gy / 20.0);

  double gyroZrate = -((double)gz / 20.0);

 

  gyroXangle += gyroXrate*((double)(micros()-timer)/1000000);

  gyroYangle += gyroYrate*((double)(micros()-timer)/1000000);

  gyroZangle += gyroZrate*((double)(micros()-timer)/1000000);

  Serial.println(gyroXangle);

  Serial.println(gyroYangle);

  Serial.println(gyroZangle);

 

                       //(step delay, M1, M2, M3, M4, M5, M6);

  Braccio.ServoMovement(0,           gyroZangle,  gyroYangle/2, gyroYangle, gyroYangle/2, gyroXangle,  73);

 

timer = micros();

 

  delay(1);

 

}

 

The code was not easy to frame. Had several trial and error methods to do it, but finally was able to do it. It wouldn't have been possible without the help of a friend in the lab Kishan Chavda.

 

The video of testing can be found below at the end of page.

Using Mobile Application

 

The next method I wanted to try was to use a mobile application to control the servo motors.

 

https://www.hackster.io/KureBasRobotics/gesture-controlled-trainable-arduino-robot-arm-via-bluetooth-4a1e57

The above link was really really useful in helping me understand how to make it possible. I used the same app that's being used in the tutorial and modified the code.

Code

#include <Wire.h>

#define MIN_PULSE_WIDTH       650

#define MAX_PULSE_WIDTH       2350

#define DEFAULT_PULSE_WIDTH   1500

#define FREQUENCY             50

#include <Braccio.h>

#include <Servo.h>

 

Servo base;

Servo shoulder;

Servo elbow;

Servo wrist_rot;

Servo wrist_ver;

Servo gripper;

int servo1;

int servo2;

int servo3;

int servo4;

int servo5;

int servo6;

 

void setup() {

  Serial.begin(9600);

   Braccio.begin();

}

 

void loop() {

 

  if(Serial.available()>= 2 )

  {

    unsigned int servopos = Serial.read();

    unsigned int servopos1 = Serial.read();

    unsigned int realservo = (servopos1 *256) + servopos;

    Serial.println(realservo);

 

    if (realservo >= 1000 && realservo <1180){

    int servo1 = realservo;

    servo1 = map(servo1, 1000,1180,0,180);

    Braccio.ServoMovement(20,           servo1,  15, 180, 170, 0,  73);

    delay(10);

 

    }

 

    else if (realservo >=2000 && realservo <2180){

      int servo2 = realservo;

      servo2 = map(servo2,2000,2180,0,180);

       Braccio.ServoMovement(20,           0,  servo2, 180, 170, 0,  73);

      delay(10);

 

    }

 

  else  if (realservo >=3000 && realservo < 3180){

      int servo3 = realservo;

      servo3 = map(servo3, 3000, 3180,0,170);

       Braccio.ServoMovement(20,           0,  15, servo3, 170, 0,  73);

      delay(10);

    }

  else  if (realservo >=4000 && realservo < 4180){

      int servo4 = realservo;

      servo4 = map(servo4, 4000, 4180,0,180);

        Braccio.ServoMovement(20,           0,  15, 180, servo4, 0,  73);

      delay(10);

    }

 

   else if (realservo >=5000 && realservo < 5180){

      int servo5 = realservo;

      servo5 = map(servo5, 5000, 5180,0,180);

        Braccio.ServoMovement(20,           0,  15, 180, 170, servo5,  73);

      delay(10);

    }

 

   else if (realservo >=6000 && realservo < 6180){

      int servo6 = realservo;

      servo6 = map(servo6, 6000, 6180,10,73);

       Braccio.ServoMovement(20,           0,  15, 180, 170, 0,  servo6);

      delay(10);

    }

 

  }

 

}

 

int pulseWidth(int angle)

{

  int pulse_wide, analog_value;

  pulse_wide   = map(angle, 0, 180, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);

  analog_value = int(float(pulse_wide) / 1000000 * FREQUENCY * 4096);

  return analog_value;

}

 

To explain one loop of the servo, the value is first defined within a range like in case of servo 2 its 2000 to 2180 and then mapped. The range will vary from 0 to 180 and the last part is making the servo move accordingly.

Braccio with MPU6050 and Bluetooth

Flex Sensor

 

I was able to control the arm using the gyro sensor but was not able to control the gripper. So as suggested by my regional instructor Ohad, I decided to make a flex sensor to control the gripper.

I searched online on how to make a flex sensor and there are numerous references on youtube and Instructables, to begin with.

The working of the flex is quite simple. It has a layer of resistive material in between to electrodes and the change in resistance is measured when the sensor is bent.

 

-flex sensor is sensors that change in resistance depending on the amount of bend on the sensor.

 

-they convert the change in the bend to electrical resistance- the more the bend, the more the resistance value.

 

-flex sensor produces is analog value

There is a particular way to connect the sensor and the diagram for the same.

 

As per the various tutorials I saw on the net the requirements were simple. The following are the material requirement.

 

-Paper

-Copper sheet / Aluminium foil

-Jumper wires

-Insulation tape

-A piece of plastic sheet

-Pencil

DIY Flex Sensor

The first step is to measure the size desired(size of your finger) and then cut the plastic, paper and copper in that size.

Cutting Materials to Strips

I used a pencil and scribbled over the paper on both sides. This is very important as this is the resistive material that is used to measure the resistance.

Making Resistive paper

The next part was to fix the jumper to each of the copper strips.

Copper Strip with Jumper

This part is basically sandwiching all the materials and packing them. I placed the insulation tape, on them the plastic sheet and then the copper strip. The plastic strip is just to bring the sensor back to upright position when bent.

 

The final layer or the middle layer is the scribbled paper.

Making Flex Sensor

I then packed all the layers and this is the final flex sensor.

Flex Sensor

I used a multimeter to measure the resistance from the flex sensor but I wasn't able to measure any values. I checked all my connections and everything was fine. The mistake I made was the paper scribbling. The dark the scribbling the better the resistance value. So I had to remove the paper and make it darker.

 

Note: Another way to check the flex sensor values is my checking the voltage from it. The program for that can be found in Arduino example programs

File>Examples>Basic>Analog voltage

Flex Sensor

This flex sensor worked. =)

Now I had to change the previously written code slightly to accommodate the flex sensor and to control the gripper.

Code

#include <Braccio.h>

#include <Wire.h>

#include <I2Cdev.h>

#include <MPU6050.h>

#include <Servo.h>

 

Servo base;

Servo shoulder;

Servo elbow;

Servo wrist_rot;

Servo wrist_ver;

Servo gripper;

MPU6050 accelgyro;

 

int16_t ax, ay, az;

int16_t gx, gy, gz;

 

double accXangle;

double accYangle;

double accZangle;

 

double gyroXangle = 180;

double gyroYangle = 180;

double gyroZangle = 180;

 

uint32_t timer;

void setup()

{

  pinMode(A0,INPUT);

 

  Braccio.begin();

  Wire.begin();

 

  Serial.begin(38400);

 

 

  Serial.println("initiate I2C");

 

  accelgyro.initialize();

 

 

  Serial.println("Testing Connection");

  Serial.println(accelgyro.testConnection() ? "MPU6050 Connected Successfully" : "Connection Unsuccessful");

  timer = micros();

}

 

void loop()

{

  int sensorValue = analogRead(A0);

  float voltage = sensorValue * (5.0 / 1023.0);

  Serial.println(voltage);

 

  accelgyro.getMotion6(&ax, &ay, &az, &gx, &gy, &gz);

 

 

  accXangle = (atan2(ax,az) + PI) * RAD_TO_DEG;

  accYangle = (atan2(ay,az) + PI) * RAD_TO_DEG;

  accZangle = (atan2(ax,ay) + PI) * RAD_TO_DEG;

 

  double gyroXrate = ((double)gx / 100.0);

  double gyroYrate = -((double)gy / 100.0);

  double gyroZrate = -((double)gz / 100.0);

 

 

  gyroXangle += gyroXrate*((double)(micros()-timer)/1000000);

  gyroYangle += gyroYrate*((double)(micros()-timer)/1000000);

  gyroZangle += gyroZrate*((double)(micros()-timer)/1000000);

 // Serial.println(gyroXangle);

  //Serial.println(gyroYangle);

  //Serial.println(gyroZangle);

 

 

                       //(step delay, M1, M2, M3, M4, M5, M6);

 // Braccio.ServoMovement(0,           gyroZangle,  gyroYangle/2, gyroYangle, gyroYangle/2, gyroXangle,  10);

 

 

//timer = micros();

if(voltage >= 0.14)

  {

  //Braccio.ServoMovement(15,           gyroZangle,  gyroYangle/2, gyroYangle, gyroYangle/2, gyroXangle,  73);

  //gripper.write(73);

base.write(gyroZangle);

shoulder.write(gyroYangle/2);

elbow.write(gyroYangle);

wrist_rot.write(gyroYangle/2);

wrist_ver.write( gyroXangle);

gripper.write(73);

 timer = micros();

  }

else

  {

    //Braccio.ServoMovement(15,           gyroZangle,  gyroYangle/2, gyroYangle, gyroYangle/2, gyroXangle,  10);

    //gripper.write(10);

     base.write(gyroZangle);

shoulder.write(gyroYangle/2);

elbow.write(gyroYangle);

wrist_rot.write(gyroYangle/2);

wrist_ver.write( gyroXangle);

gripper.write(10);

timer = micros();

  }

 //gripper.write(10);

  delay(1);

 

 

}

Braccio with MPU6050+Flex Sensor

Conclusion

 

Robotics is something that completely new to me. Since my instructor, Rudrapal was kind enough to lend me his robot arm I was able to experiment with it. There are so many factors that affect the arm and the primary element that needs to be masters of the arm is the stepper motor. So, in fact, to learn to control the arm one needs to understand the entire working of the arm. Learning about the arm was quite nice but programming it to do task wasn't very easy as I am new to programming. On the whole, the week filled with the learning process.

Files

 

All files can be downloaded from HERE

WEEK 17

Wildcard week. The main objective of this week is to experiment with any process that involves digital process like laser cutting, CNC milling, 3d printing etc. Neil spoke about composites in detail. He started about the different material that can be used for composites and then he went on about the vendor. Composites involve both digital process and physical process of making the mold. As there are different kinds of composites he explained about the safety of each.