Final Project Document (Autosaved) 1

download Final Project Document (Autosaved) 1

of 97

Transcript of Final Project Document (Autosaved) 1

  • 7/26/2019 Final Project Document (Autosaved) 1

    1/97

    Faculty of Engineering, the Built Environment & IT

    Technology for tomorrow

    Department of Mechatronics

    Microcontroller-Based Control for Robot Arm

    Compiled by:Todd T Munemo

    Supervisor:Dr. Farouk Smith

    2012

  • 7/26/2019 Final Project Document (Autosaved) 1

    2/97

    Page | 1

    i Authentication

    I Todd Munemo hereby declare that all work done in this project is my own and that I had no

    assistance from outsiders (unless authorized by the Mechatronics department). I declare that

    all references have been duly acknowledged.

    Signed

    .........................................

    Todd Munemo

  • 7/26/2019 Final Project Document (Autosaved) 1

    3/97

    Page | 2

    Contentsi Authentication ............................................................................................................................................ 1

    iii Synopsis ..................................................................................................................................................... 5

    iv List of Acronyms ........................................................................................................................................ 6

    1 Introduction ............................................................................................................................................... 7

    2 Problem Analysis and System Requirements ............................................................................................. 8

    2.1 Background ......................................................................................................................................... 8

    2.2 Design Requirements .......................................................................................................................... 9

    3 DESIGN CONCEPTS ................................................................................................................................... 10

    3.1 Concept 1 FPGA Controller ............................................................................................................ 10

    3.2 Concept 2MCU System .................................................................................................................. 11

    3.3 Concept 3MCU + MULTIPLEXER .................................................................................................... 12

    3.4 Comparison Matrix ........................................................................................................................... 13

    4 FINAL DESIGN AND SPECIFICATIONS........................................................................................................ 14

    4.1 Mechanical System ........................................................................................................................... 16

    4.1.1 Robot Arm .................................................................................................................................. 16

    4.1.2 Force Sensor ............................................................................................................................... 19

    4.1.3 Servo Motors .............................................................................................................................. 21

    4.2 Electrical System ............................................................................................................................... 21

    4.2.1 The Robot Cable ......................................................................................................................... 22

    4.2.2 The Arduino Mega 2560............................................................................................................. 23

    4.2.3 H-Bridge Driver Module ............................................................................................................. 24

    4.2.4 Optical Encoders ........................................................................................................................ 25

    4.2.5 Limit Switches ............................................................................................................................ 27

    4.2.6 Power Supplies ........................................................................................................................... 27

    4.2.7 LCD ............................................................................................................................................. 27

    4.3 The Hardware Control Circuit ....................................................................................................... 28

    4.4 Control System and IT ....................................................................................................................... 28

    4.4.1 Main Program ............................................................................................................................ 29

    4.4.2 The Homing Subroutine ............................................................................................................. 30

  • 7/26/2019 Final Project Document (Autosaved) 1

    4/97

    Page | 3

    4.4.3 The Pick Subroutine ................................................................................................................... 32

    4.4.4 The Place Subroutine ................................................................................................................. 34

    4.5 Operation Description ....................................................................................................................... 35

    4.5.1 Operation Sequence .................................................................................................................. 35

    4.5.2 Safety ......................................................................................................................................... 35

    5 Design and Development Procedure ....................................................................................................... 36

    5.1 Introduction ...................................................................................................................................... 36

    5.2 Mechanical ........................................................................................................................................ 36

    5.1.2 Gear transmission mechanisms ................................................................................................. 36

    5.2 Electrical ............................................................................................................................................ 43

    5.2.1 Encoder Circuit Design ............................................................................................................... 43

    5.2.2 Limit switch and Pushbutton circuit design ............................................................................... 47

    5.2.3 Force Sensor Circuit design ........................................................................................................ 49

    5.2.4 Power Supply unit selection ....................................................................................................... 51

    5.3 Robot Kinematics .............................................................................................................................. 51

    5.3.1 DenavitHartenberg Forward and Inverse Kinematics ............................................................. 51

    5.3.2 Geometric approach to inverse kinematics ............................................................................... 55

    5.3.4 Sample calculations .................................................................................................................... 58

    5.4 Position Control of the robot arm ..................................................................................................... 59

    5.4.1 Position Control System ............................................................................................................. 59

    5.4.2 Optical Encoder decoding .......................................................................................................... 60

    5.4.4 Calibration Procedure ................................................................................................................ 61

    5.4.4 Base Position Control ................................................................................................................. 63

    5.4.5 Shoulder Position Control .......................................................................................................... 66

    5.4.6 Elbow Position Control ............................................................................................................... 68

    5.4.7 Gripper Control .......................................................................................................................... 69

    5.6 IT........................................................................................................................................................ 69

    5.6.1 User Interface and Serial Communication ................................................................................. 69

    6 Performance Evaluation, Experiments and Data Analysis ....................................................................... 71

    6.1 Duty Cycle Variation with Error ........................................................................................................ 71

    6.2 Accuracy ............................................................................................................................................ 72

    6.2.1 Comparison of Theoretical and Calibration Performance ......................................................... 73

  • 7/26/2019 Final Project Document (Autosaved) 1

    5/97

    Page | 4

    6.3 Speed................................................................................................................................................. 75

    7 Conclusions .............................................................................................................................................. 76

    8 References ............................................................................................................................................... 78

    APPENDIX ACOMPONENT SPECIFICATIONS ............................................................................................ 81

    A-1 FlexiForce A401 sensor ..................................................................................................................... 82

    A-2 Arduino Mega ................................................................................................................................... 83

    A-3 H-Bridge Driver ................................................................................................................................. 84

    A-4 Meanwell Power Supply ................................................................................................................... 85

    A-1 Arduino Mega Schematic ................................................................................................................. 86

    APPENDIX BHARDWARE CONTROL CIRCUIT BILL OF MATERIALS ........................................................... 87

    APPENDIX C - EXPERIMENTS ....................................................................................................................... 88

    C-1 Encoder Circuit Testing ..................................................................................................................... 89

    C-2 Base Calibration ................................................................................................................................ 91

    C-3 Shoulder Calibration ......................................................................................................................... 92

    C-4 Elbow Calibration .............................................................................................................................. 92

    C-5 Accuracy and Duty Cycle ................................................................................................................... 93

    C-6 Theoretical against Calibration performance ................................................................................... 94

    APPENDIX D PROGRAM CODE.................................................................................................................. 95

    APPENDIX ETHE HARDWARE CONTROL CIRCUIT .................................................................................... 96

  • 7/26/2019 Final Project Document (Autosaved) 1

    6/97

    Page | 5

    iii Synopsis

    A robot arm controller was designed as a final year project. The project involved designing a

    robot controller that would control a five axis robot to perform pick and place tasks. The

    designed controllers performance is to be compared with the original controller which was

    designed by Eshed Robotec. The robot had a speed of 330mm/sec and a repeatability of +/-0.05mm when it was manufactured (Eshed Robotec, 1995:2-3). The programming language has

    to be based on the C programming environment.

    Three concepts were evaluated and the final design was adapted from the best design concept

    which has microcontroller at its core. This design was chosen because the Arduino Mega

    microcontroller had enough ports to accommodate all the inputs and also because there is a lot

    of support available for the Arduino on the internet.

    The design allows the user to enter coordinates for pick and place tasks in the robot workspace.The inverse kinematics method then converts the Cartesian coordinates entered by the user

    into joint angles to which the robot has to be moved. The encoders on the motors are used as

    feedback to control the positioning of the robot joints. Communication between the user and

    computer is done through a user interface created on the Arduino serial monitor.

    The performance of the robot was evaluated and satisfactory results were attained. The key

    performance parameters were achieved to a satisfactory degree due to the fact that the robot

    has gone through a wear and tear process over the years. The controller designed managed to

    execute the pick and place task as required.

  • 7/26/2019 Final Project Document (Autosaved) 1

    7/97

    Page | 6

    iv List of Acronyms

    Acronym Definition

    MCU Microcontroller

    FPGA Field programmable gate array

    I/O Input/output

    IC Integrated Circuit

    kB kilobyte

    PWM Pulse width modulation

    USB Universal Serial Bus

    ICSP In-circuit Serial programming

    IK Inverse Kinematics

    IP Intellectual Property

    D-H Denavit-Hartenberg

  • 7/26/2019 Final Project Document (Autosaved) 1

    8/97

    Page | 7

    1 Introduction

    The purpose of this project is to design a microcontroller based controller for a five axis robot

    arm to perform a simple pick and place task. According to Spong et al (2006:10), a robot is a

    reprogrammable, multifunctional, manipulator designed to move material, parts, tools, or

    specialised devices through variable programmed motions for the performance of a variety oftasks. The controller is to be implemented on a SCORBOT ER III robot arm designed by Eshed

    Robotics. The purpose of the controller design is to replace the old controller which was

    removed from the robot. This design task is to be completed as a final year BEng Mechatronics

    project requirement. A microcontroller (MCU) is a small computer on a singleintegrated circuit

    containing a processor core, memory, and programmableinput/output peripherals. The MCU is

    the backbone of the whole controller design; it performs all the logical operations involved in

    controlling the robot to perform a pick and place task.

    Robots are extensively used in the manufacturing industry where a lot of repetitive work is

    done because of their high repeatability and accuracy when compared to humans. Robots are

    also becoming important in most industries as well (Fernandez et al, 2012:50). The Robot arm is

    the most common amongst all manufacturing robots and is used for various manufacturing

    processes which include spray painting, welding and assembly operations (Iqbal et al,

    2012:300). Usually servo motors are used to control the movement of all the robot joints as the

    feedback obtained from their encoders is vital for the precise control of the robots motion.

    Sensors are also incorporated in robot arms to detect any foreign obstacles and to prevent

    dropping or breaking any loaded components in its gripper.

    This document analyses the problem at hand and various concepts are generated to developthe final controller design, with specific attention given to the key performance parameters

    required as highlighted in the problem statement. The final design is developed from the best

    concept design which is selected through the aid of a comparison matrix. The entire design is

    split into the analysis of mechanical, electrical and Information Technology (IT) components. A

    robot hardware control circuit was designed through the application of standard engineering

    principles.

    The performance of the designed and assembled model was finally evaluated. The robots

    repeatability was found to be +/- 12.6mm which differs greatly from that of the manufacturer,

    which is rated +/- 0.05mm. The speed of the robot was found to be 26.65 mm/s, which is very

    slow compared to the manufacturers rated speed of 330mm/sec. The huge difference between

    the manufacturers repeatability and that of the designed controller can be attributed to

    reduction in accuracy of the base which as it had the largest positioning standard error of +/-

    3.4mm.The base was driven at a low speed to minimise the positioning error, resulting in a

    http://en.wikipedia.org/wiki/Integrated_circuithttp://en.wikipedia.org/wiki/Input/outputhttp://en.wikipedia.org/wiki/Input/outputhttp://en.wikipedia.org/wiki/Integrated_circuit
  • 7/26/2019 Final Project Document (Autosaved) 1

    9/97

    Page | 8

    great reduction of the robots speed. Overally the pick and place task was successfully

    completed.

    2 Problem Analysis and System Requirements

    The aim of the overall system is to design a microcontroller or FPGA based controller for a 5-

    axis robot arm to perform a simple pick and place task.

    2.1 Background

    The SCORBOT-ER III is a robot teaching device that was developed in the early 80s due to the

    progress achieved in robotics and industry globally. This robot came with its own dedicated

    controller which had a unique program modular training that allowed instructors to conduct

    robotics courses for students. This allowed the students to get the opportunity of handling

    robot systems.

    The robots joints are all revolution in type. The arm is constructed as a five degrees of freedom

    articulated arm (base, shoulder, elbow, wrist roll and pitch) which are all driven by DC motors

    with shaft encoders on their axes.

    Figure 1: Scorbot ER-III robot arm

  • 7/26/2019 Final Project Document (Autosaved) 1

    10/97

    Page | 9

    2.2 Design Requirements

    The main focus of this design project is to design a controller for the SCORBOT ER-III. The

    available components are:

    The robotic arm (SCORBOT ER-III)

    The Altera Cyclone III development board or MCU development board H-bridge drivers

    The robot controller design mainly focuses on the IT and electrical circuit design aspects while

    the mechanical aspect entails gear ratio calculations.

    The following calculations are critical to the design process:

    Inverse Kinematics calculations are required to determine the joint angle parameters to

    facilitate the pick and place tasks of the robot.

    The gear train transmission relationships need to be determined for the calculation of

    the encoder resolution for the various joints. The resolution is defined as the smalleststep achievable by turning gears (or engines, or joints, etc.).The usual practice is to

    define this step in degrees (angular resolution) or units of length (linear resolution).

    The electrical part of the design involves the development of a control circuit that interfaces the

    inputs and outputs of the system with the MCU. The outputs from the quadrature encoders,

    limit switches and force sensor are to be fed back into the MCU. Limit switches help to

    determine the robots home position and also assist in restraining the joint motions to their

    maximum angle of rotation to avoid joint collisions. Quadrature encoders provide feedback on

    the joint DC motors direction speed and position. The force sensor regulates the grippershandling force.

    The control circuit should generate pulse width modulated (PWM) signals which required to run

    the DC motors that drive the joints of the robot. PWM signals are varying digital signals which

    average the voltage to the servomotors and thus control the motor speed. The PWM signal

    generated by the MCU is supplied to the servomotors through the H-Bridge drivers, since an

    MCU only supplies a maximum of 5V on its output and does not have enough power to run the

    12V DC motors.

    The software design aspect involves developing algorithms for inverse kinematics computations

    and motor position control. The control system of the robot should be implemented in C

    language programming.

  • 7/26/2019 Final Project Document (Autosaved) 1

    11/97

    Page | 10

    The technical performance measures that need to be taken into consideration for the controller

    design are:

    Accuracy: - the robot should accurately pick an object at the specified pick

    position and must also accurately place the object.

    Repeatability: -The pick and place task must be performed repeatedly with thespecified level of accuracy.

    Speed: - The pick and place task should be performed as fast as possible.

    Efficiency: -An optimized trajectory is required for the pick and place task.

    3 DESIGN CONCEPTS

    The design concepts generation involves the development of a hardware control circuit for the

    SCORBOT ER-III robot arm. Three concepts are generated and the best concept is selected with

    the aid of a comparison matrix.

    3.1 Concept 1 FPGA Controller

    Figure 2 : The FPGA controller concept

    The first concept has a FPGA controller at its core and four H-bridge servo drivers (see Figure 2).

    The main purpose of the central controller is to execute the computation of the motion

    trajectory and inverse kinematics. The central controller integrated circuit (IC) comprises of two

    intellectual properties (IPs); one is dedicated to the computation of inverse kinematics of the

  • 7/26/2019 Final Project Document (Autosaved) 1

    12/97

    Page | 11

    robot while the other is responsible for performing the functions of the trajectory motion in

    software. The encoders provide feedback on the robot position to the central controller. At

    least 34 digital 10 pins are required for the encoder feedback, PWM, motor control and limit

    switch detection.FPGAs have sufficient ports; for example the Altera Stratix II EP2S60F672C5ES

    FPGA has 718 I/O ports which are more than enough (Kung & Chen, 2008:292). FPGAs are notsuited for floating point computations which are required for the Inverse kinematics method of

    expressing Cartesian coordinates in terms of the robot angle parameters (Toh et al, 2009:448).

    FPGAs can perform floating point calculations but such a task requires a vast amount of logic

    cells to conduct calculations. According to Edwards (2011:1) FPGA code requires specialised

    talent; this is due to the time and tedious demands of the iterative nature of FPGA code

    development and the associated long synthesis/simulation/execution design cycle, thus there is

    a risk of not completing the project on time since the author is not familiar with FPGAs. The

    development time of the FPGA hardware is long as different modules need to be fastened and

    tested to perfection before the FPGA can be used. They are also generally expensive.

    3.2 Concept 2 MCU System

    Figure 3 : The MCU system concept

    The second concept (see Figure 3) is similar in structure to the first, but it has a MCU at the

    center of the robot control hardware. The MCU supplies PWM signals to the H-bridge drivers

    and takes feedback from the quadrature encoders, limit switches and the force sensor. Unlike

    the FPGA, MCUs address floating point calculations with well-developed vector math engines,

    which means that their processors are well designed for simple math calculation (Edwards,

    2011:1). FPGA development often takes much longer than microprocessor development for an

    equivalent task using a high-level language like C or C++ (Edwards, 2011:1).The MCU also has in

    built functions for quadrature encoder decoding and PWM signal generation required by the

  • 7/26/2019 Final Project Document (Autosaved) 1

    13/97

    Page | 12

    motors. MCUs are much lower in cost as compared to FPGAs for small applications and large

    quantities. MCUs however are always sequential and therefore less flexible than FPGAs which

    are can execute code in parallel or sequentially. Programming requires long lines of code which

    complicates structuring and debugging. At least 34 digital IO pins are required and the main

    problem of implementing the MCU concept lies in its shortage of sufficient I\O pins. Thisproblem can be solved by settling for bigger MCUs with more pins, but the problem is that they

    come at a higher cost.

    3.3 Concept 3MCU + MULTIPLEXER

    Figure 4 : The MCU + MUX concept

    The third concept (see Figure 4) tries to find a solution to the inadequacies of the second

    concept by introducing a multiplexer such that a smaller MCU which comes at a lower cost canbe used. In order to read all the 8 digital inputs from encoders, a multiplexer board is added to

    the MCU system presented earlier. This reduces the demand of pins on the MCU. The motors

    are controlled by the MCU via H-bridge drivers. The multiplexer (MUX) is connected to the MCU

    to facilitate signal selection by the MCU. The hardware implementation is less complex

    compared to the FPGA design and is manageable. The third concept however requires more

  • 7/26/2019 Final Project Document (Autosaved) 1

    14/97

    Page | 13

    programming as the functionality of the multiplexer also has to be included in code. The other

    disadvantage is that only one encoder channel is processed at a particular time, this increases

    the cycle time of the pick and place task as the motors will have to be run sequentially since

    one motor can be controlled at a particular time.

    3.4 Comparison Matrix

    The three concepts are evaluated with the aid of a comparison matrix (see Table 1), with 5

    being the most favourable rating, 3 being the value given to second best concept on a particular

    performance parameter and zero being the least. The three concepts are compared based on

    the following parameters:

    Easy hardware Implementation

    Ease of programming

    Processing speed

    Flexibility Low Cost

    Efficiency

    Table 1 : The Comparison matrix

    FPGA MCU MCU + MUX

    Easy Hardware Implementation 0 5 0

    Ease of Programming 0 5 3

    Shorter cycle time 5 3 0

    Flexibility 4 0 0

    Efficiency 5 3 0

    Cost 0 3 5

    Total 14 19 8

    The MCU concept most has the most favourable points for the ease at which the hardware can

    be implemented parameter, the main reason being the fact that the MCU comes with most, if

    not all its peripheral devices unlike the FPGA which does not come with all hardware

    peripherals. The MCU +MUX is the second best because there is need for the addition of the

    multiplexer unlike a bigger MCU which can be directly interfaced with the encoders since it has

    enough pins. The FPGA has the least score on the Ease of programming parameter; the main

    contributing factor is because it is easier to program a MCU compared to an FPGA. The

    MCU+MUX concept was second best because there is need to program more code for channel

    selection on the multiplexer, thus making it more complicated than the MCU concept.

  • 7/26/2019 Final Project Document (Autosaved) 1

    15/97

    Page | 14

    The FPGA concept is the most flexible since can be used to execute both sequential and parallel

    code unlike the MCUs which execute the code sequentially. The FPGA has the shortest cycle

    time since all motors can be controlled simultaneously because of its parallel functionality .The

    FPGA is more expensive than a MCU(Edwards,2011:1) thus it has the lowest score on cost.

    From table 1, the MCU system has the highest score therefore the ideas from this conceptgreatly contributed to the final design.

    4 FINAL DESIGN AND SPECIFICATIONS

    Motor 1(Base)

    Motor 2(Shoulder)

    Motor 3(Elbow)

    Motor 4(Wrist Pitch)

    Motor 5(Wrist Roll)

    Motor 6 (Gripper)

    MCU

    (Arduino Mega 2560)6 rotary encoders

    5 Limit Switches

    Force Sensor

    FlexiForce(A401)

    Dual H-Bridge 2

    L298

    Dual H-Bridge 3

    L298

    Dual H-Bridge 1

    L298

    Figure 5 : Final controller design

    The final design (see Figure 5) is very similar to concept 2 and has an Arduino Mega 2560 as the

    core of the hardware design. The Arduino MEGA is a MCU board based on the Atmega2560.This

    MCU overcomes the main problem of the second concept as it has 54 I/O pins which are

    sufficient for controlling the robot. Two dual H-Bridge driver modules based on the ST L298 dual

    full bridge driver are used to power the robots DC motors. The sensors, limit switches and

    encoders are connected as inputs to the MCU.The MeanWell power supply, which is a 12VDC

    power supply is used to power the motor H-Bridge drivers. For the final design only four axes

    are controlled and they are:

    Shoulder

    Base

    Elbow

    Gripper

  • 7/26/2019 Final Project Document (Autosaved) 1

    16/97

    Page | 15

    The wrist roll is fixed at 180 degrees and the wrist pitch is fixed such that the gripper angle is

    always -90 degrees. The four axes are sufficient for performing the pick and place task. This

    decision reduces the complexity of the inverse kinematics and the motion control algorithm.

    Figure 6: Final design model

  • 7/26/2019 Final Project Document (Autosaved) 1

    17/97

    Page | 16

    4.1 Mechanical System

    4.1.1 Robot Arm

    Figure 7 : Scorbot ER-III joint positions (Eshed Robotec: 1995)

    The mechanical system of this project is SCORBORT ER-III (see Figure 7) robot which was

    described earlier in the problem statement. This articulated arm has five degrees of freedom

    (base, shoulder, elbow and the wrist which has two movements and the gripper which can be

    considered as the sixth axis). With exception of the gripper which is moves linearly when in

    motion, all the joints exhibit a rotational motion about their axes. The SCORBOT ER-III has a

    mountable base with six holes to keep it secure from movement during operation. The axes of

    the robot are driven by 12V DC servomotors with shaft encoders on their axles; the encoders

    facilitate closed loop control of the servomotors. The servomotors have a reduction gear box so

    that the output shaft of the gearbox rotates at lower speed than the armature coils of the

    motors. A positive DC supply rotates the robot servomotors in one direction and a negative

    supply rotates the robot in the other direction. The elbow is driven by a servomotor through an

    indirect coupling system. Indirect coupling refers to a system where the motor is mounted

    away from the joint and the motion of the motor is transmitted via transmission systems such

    belts which have a small weight when compared to gears. The indirect coupling system is

    implemented because it reduces the weight of the arm.The locations of the robot motors are

  • 7/26/2019 Final Project Document (Autosaved) 1

    18/97

    Page | 17

    shown in Figure 8.The mechanical arm has five limit switches with each joint having one; these

    switches help to prevent collisions between joints. They also help in the determination of the

    Hard Home position, which refers to the robot orientation when all limit switches are

    activated.

    Figure 8 : DC servomotor locations (www.repostorio.bib.upct.es/dspace)

    Mechanical Structure: Vertically Articulated, 5 Axis PLUS Gripper = 6 Axis

    Figure 9 : The Scorbot ER-III workspace (Eshed Robotec: 1995)

  • 7/26/2019 Final Project Document (Autosaved) 1

    19/97

    Page | 18

    The robot had the following specifications when it was manufactured by Eshed Robotec:

    Working Envelope (see Figure 9):

    Axis 1: Base Rotation 310 degrees

    Axis 2: Shoulder Rotation +130 Degrees / -35 Degrees

    Axis 3: Elbow Rotation +- 130 Degrees

    Axis 4: Wrist Pitch +- 130 Degrees

    Axis 5: Wrist Roll Unlimited

    Axis 6: Gripper Open/Close + Measurement of gripper opening

    Maximum Working Radius: 61mm (24.4")

    Gripper Opening: 75mm (3") without rubber pads - 65mm (2.56")

    with rubber pads

    Maximum Work Load: 1kg (2.2 lbs.)

    Transmission: Gears, Timing Belts and Lead Screw

    Actuators: 6 DC Servo Motors with Closed-Loop Servo Control

    Feedback: Optical Encoders on All Axes

    Hard Home: Fixed Reference Position on all Axes

    Repeatability: +- .05mm (+- 0.02")

    Maximum Speed: 330mm/Sec. (13"/Sec)

    Weight: Robot Arm: 11kg (24 lbs.) - Controller: 5kg (11 lbs.)

  • 7/26/2019 Final Project Document (Autosaved) 1

    20/97

    Page | 19

    4.1.2 Force Sensor

    Figure 10 : FlexiForce A401 force sensor (Tekscan: 2012)

    Tekscans FlexiForce A401 (see Figure 10) sensor is used to measure the gripping force of the

    robot. This sensor is a durable piezoresistive sensor that senses a contact force. A piezoresistive

    sensors resistance value changes when it is squeezed by a force. According to (Eshed

    Robotec,2012: 2-3), the robot can pick a maximum of 1kg mass.For the selection of a force

    sensor, a force analysis is done on the gripper. The force sensor should be able to detect the

    maximum operating force of the gripper. The gripper exerts this force when handling the 1kg

    mass.

  • 7/26/2019 Final Project Document (Autosaved) 1

    21/97

    Page | 20

    Figure 11: Gripper force diagram

    The force sensor detects N , which is the compression force exerted on the vertical sides of themass M shown in figure 11.The force sensor is placed between one vertical side of the block

    and the gripper rubber pads.F1 and F2 represent the frictional forces required to prevent the

    mass from falling due to gravity. To determine the force N1 the following equations are used:

    a represents the acceleration due to gravity, which is 9.81m/s

    2 on earth. This equation is

    derived from Newtons third law of motion.

    Where F representsthe frictional force,N represents the normal force and =0.7 is the

    coefficient of friction between rubber and wood (since the gripper has rubber pads and

    the load being lifted is made of wood).

    The summation of forces in the vertical direction is done to calculate the F2.

  • 7/26/2019 Final Project Document (Autosaved) 1

    22/97

    Page | 21

    Therefore: = 9.81 N

    Making N subject of the formula:

    Therefore, the maximum force that can be detected by the force sensor is 7N.The Tekscan A401

    sensor was chosen because it can take a maximum of 110N.The forces to be exerted on the

    gripper vary between 0-7N.These forces fall within the range of the selected force sensor which

    is between 0N and 110N, which makes the selected sensor suitable for this application. The

    specifications of the sensor can be found in APPENDIX A-1.

    4.1.3 Servo Motors

    The SCORBOT ER- III joints are run by Pittman G9000 series motors. These motors operate with

    a voltage of 12V DC and the maximum current they can take is 2A (Eshed Robotec, 1995: F-

    2).Therefore a power supply of at least 12VDC is required to power the motors.

    4.2 Electrical System

    Figure 12: Controller box

  • 7/26/2019 Final Project Document (Autosaved) 1

    23/97

    Page | 22

    The main elements of the electrical system are:

    Robot cable

    Arduino Mega 2560

    H-Bridge Driver Modules

    Optical Encoders

    Limit Switches

    Power Supply

    The electrical system is the core of this project, and it is basically the integration of the various

    electrical elements listed above to form a hardware control circuit. The electrical elements,

    their functionality and integration into the final design are described in the report.

    4.2.1 The Robot Cable

    The operational and control commands of the robot are transmitted through this cable, which

    is the link between the robot arm and the controller. The cable runs from the base of the robot

    arm to the controller. The cable has 48 leads which are divided into six groups (one group for a

    single motor).Each group contains eight leads:

    2 leads supply voltage to the motor.

    2 leads receive pulses from the optical encoder (channel 0 and

    channel 1).

    1 lead carries the signal from the limit switch.

    1 lead supplies voltage to the encoder (VLED).

    1 lead provides the ground for the limit switch.

    1 lead provides the ground for the encoder.

    Only four of the six groups of leads are required to control the base, shoulder, elbow and

    gripper.

  • 7/26/2019 Final Project Document (Autosaved) 1

    24/97

    Page | 23

    4.2.2 The Arduino Mega 2560

    Figure 13 : Arduino Mega 2560 front (www.arduino.com)

    This MCU board (see Figure 13) is the heart of the robot control system. As earlier stated, the

    board is based on the Atmega2560. The Arduino has 54 digital I/O pins, of which 14 can be

    implemented as PWM outputs, 16 as analog inputs, 4 as UARTs(hardware serial ports), a

    16MHz crystal oscillator, a USB connection, a power jack, an ICSP header, and a reset button.

    The pins operate at 5V.Eeach pin has an internal pull-up resistor (20-50 k) and can provide or

    receive a maximum of 40mA of current. This MCU has an input impedance which varies from

    100k - 1M.The MCU board is any easy to use device, to get started it can be powered by

    simply connecting it to a computer via a USB cable or a battery. The Mega series of the Arduinowas mainly chosen for this task because it has sufficient I/O pins to interface with the encoders,

    limit switches and the force sensor. The Arduino is programmed in C language .The Schematic,

    Reference Design & Pin Mapping and more information on the Arduino is provided in APPENDIX

    A-2.

    http://arduino.cc/en/uploads/Main/ArduinoMega2560_r2_front.jpg
  • 7/26/2019 Final Project Document (Autosaved) 1

    25/97

    Page | 24

    4.2.3 H-Bridge Driver Module

    Figure 14 : Dual H-Bridge driver module (www.seeedstudio.com)

    The MCU cannot supply enough power to run the motors and therefore two Dual H-Bridge

    driver modules (see Figure 14) based on the ST L298 IC are used to provide the power required

    to run the motors. The ST L298 is a high voltage and current dual full bridge driver which

    accepts standard TTL logic levels and drives inductive loads such as DC motors. The enable pins

    of the driver take a PWM signal which then drives the motor at speed proportional to the

    signals duty cycle. Port A and port B are symmetrical on the module and have the same

    functionality. The word ports refers to pins which are used to connect electrical wires coming

    from the motors and the MCU to the H-bridge driver. Each port has 5 pins I1, I2, VCC, GND and

    EA, both I1 and I2 are digital ports which are responsible for controlling the motor direction. IfI1 and 12 are equal, the motor stops rotating and if I1=1 and I2=0 the motor rotates in a

    clockwise direction (see table 2).

  • 7/26/2019 Final Project Document (Autosaved) 1

    26/97

    Page | 25

    Table 2 : Dual H-Bridge driver module logic (www.seeedstudio.com)

    GND and VCC are connected to the terminals of the robots motors. The features of and

    datasheet can be found in Appendix A-3.

    4.2.4 Optical Encoders

    Figure 15 : Encoder discs for the SCORBOT ER -III (Eshed Robotec: 1995)

    The optical encoders facilitate the closed loop control of the servomotors which control the

    robotsjoints. The SCORBOT ER-III has two types of optical encoders (see Figure 15), one with

    three slots and the other with six slots. All servomotors excluding the gripper motor use the six

    slotted encoder disc type. The encoder disks are connected directly to the motor shaft and theyconsequently rotate at the same speed as the shaft. The encoder circuitry (see Figure 16)

    comprises of a printed circuit board (PC 500) which has two LEDsand two phototransistors (P0

    and P1). The encoder outputs two signals, one for each LEDphototransistor pair. The LEDs are

    connected to a 5V voltage source and they act as light sources and are mounted at opposite

    ends with the transistors. One LED-phototransistor couple is positioned near the outer

    circumference of the disc and the other at the center. The phototransistors have three

    connections (base, emitter and collector).

  • 7/26/2019 Final Project Document (Autosaved) 1

    27/97

    Page | 26

    Figure 16 : The encoder circuitry (Eshed Robotec: 1995)

    The two LED- phototransistor pairs generate tracks signals that are 90 degrees out of phase;

    this phenomenon is thoroughly described with diagrams in section 5.4.2. The speed and

    direction of the motor can be determined by monitoring the relationship between the square

    wave pulses. The angular motion can be measured by knowing the resolution of the encoder

    disk and monitoring the number of pulses using the MCUs counter. The decoding scheme that

    will be implemented in this design will involve capturing the falling edges of square wave A

    using an interrupt service routine. This scheme is also described with diagrams in section 5.4.2

    which explains how the position control is achieved through the use of optical encoders.

  • 7/26/2019 Final Project Document (Autosaved) 1

    28/97

    Page | 27

    4.2.5 Limit Switches

    Figure 17 : Limit Switch

    Each robot joint has a limit switch (see Figure17) fitted at its home position. Depression of all

    the limit switches by the cam, represents the robots hard home position, which is areference point for the robot.

    4.2.6 Power Supplies

    A power supply is required to power the H-Bridge driver modules. The motors run on a 12V DC

    voltage supply and can only take a maximum of 2A current. The Meanwell S-250-12 which is a

    12VDC power supply is used to power the system and has the following specifications

    (Meanwell, 2008:1):

    90-132VAC / 176-264VAC input Selected by switch

    Output 12V DC Rated current 18 A and the current operates on a 0-18A current

    range

    Short circuit, overload and over voltage protection

    Cooling by free air convection

    The full datasheet can be found in Appendix A-4. The MCU is powered by the USB cable

    connected to the computer. The MCU supplies 5V to the rest of the circuit with its power

    supply ports.

    4.2.7 LCD

    The Liquid crystal display (LCD) which is mounted on the front cover of the circuit box is used to

    display feedback from the inverse kinematics calculations. This allows the user to check if there

    is any error occurring from the calculations done by the MCU. The Grove serial LCD version 1.1

    which is a 16x2 character display LCD is used for interfacing with the MCU, communication is

    done serially at a baud rate of 9600kB/s. There is no particular reason why this baud rate was

  • 7/26/2019 Final Project Document (Autosaved) 1

    29/97

    Page | 28

    used; any standard baud rate will work. Communication only occurs when the arduino and the

    serial LCD are sending information at the same baud rate.

    The serial LCD is very easy to use and its interface with the Arduino only requires four pins, one

    for transmitting (Tx pin), one for receiving (Rx pin), one for VCC and the last one for GND. It

    contains a processor which takes serial data from the Arduino and displays it on the screen. It

    also accepts serial commands for conducting tasks like cursor positioning and screen clearing,

    which makes it very easy for displaying information.

    4.3 The Hardware Control Circuit

    The hardware control circuit was created using the Fritzing software which is used for designing

    arduino circuits. The Fritzing software contains schematics for Arduino MCUs and most

    electronic components. This software was used because the parts are readily available and the

    circuit drawing task is only reduced to the selection and wiring of the required components,

    which saves a lot of time. The hardware control circuit schematic shows how the motors,

    encoders, LCD and limit switches are wired together to form an electrical circuit. The hardware

    control circuit and the bill of materials of the control circuit can be found in appendix E.

    4.4 Control System and IT

    The IT part of the project deals with developing an algorithm which controls the pick and place

    task. This algorithm is downloaded to the MCU and the required subroutines to control the

    robot are executed. It also involves executing calculations for inverse kinematics and taking

    input from sensors. The inputs from the sensors are used as feedback for controlling the robot

    motors. The program was coded in the Arduino environment which is a C based language. Themain program can be divided into the pick, place and homing subroutines. Relative encoders

    are used on the robot arm. According to Sahin & Kachroo (2007:173) when robot arm joint

    movements are controlled by relative encoders, a convenient home position is achieved by

    turning all the joints counter clockwise to their limits. The homing subroutine has to be

    executed several times since the home position is the reference point for absolute positioning

    of the relative encoders. After the picking of an object, the robot goes back to the home

    position before it performs the placing task. All the robot arm movement subroutines were

    designed by the author.

  • 7/26/2019 Final Project Document (Autosaved) 1

    30/97

    Page | 29

    4.4.1 Main Program

    Start

    Homing

    Sequence

    Display

    feedback

    from limit

    switches

    Wait until user

    operator enters

    pick and place

    coordinates

    Inverse

    Kinematics

    calculations

    Display Input

    from operator

    Display Joint

    angles

    Pick Sequence

    Is picking

    sequence

    complete?

    No

    Place

    sequence

    Is the placing

    sequence

    complete?

    Yes

    End

    Yes

    No

    Display

    feedback

    Display

    feedback

    Figure 18: Flow diagram for the main program

    The main program (see Figure 18) begins by executing the homing subroutine once the system

    is started. On completion of the homing subroutine, the program prompts the operator to

    provide Cartesian coordinates for the pick and place positions. Once these coordinates are

    provided, the pick subroutine is executed. The place subroutine is executed once the picking is

    completed. Flags are set to monitor the progress of the subroutines. This facilitates the control

    of execution times for different subroutines, for example if the pick flag is set to high; thissignifies that the pick process is being executed and is thus being monitored. Thus, the place

    algorithm will only begin when the pick flag is set to low, which indicates that the pick

    algorithm is complete. Once placing is done, the program waits for the user to initiate another

    pick and place task by pressing the start button.

  • 7/26/2019 Final Project Document (Autosaved) 1

    31/97

    Page | 30

    4.4.2 The Homing Subroutine

    Start

    No

    Is base

    homing

    direction

    forward?

    Run

    shoulder

    motor

    backward

    Is shoulder

    LS==LOW?

    Run Elbow

    motor

    Forward

    No

    Is Elbow

    LS==LOW?

    Run Base

    motor

    backward

    Run Base

    motor

    forward

    Yes No

    Is Base

    LS==LOW?

    Is Base

    LS==LOW?

    Yes

    Yes

    No

    No

    Is force>=Threshold

    value?

    End

    No

    Yes

    No

    Yes

    Is pick==1?

    Yes

    Delay 10s

    Run gripper

    motor

    backward

    Is gripper

    LS==LOW?

    No

    Figure 19: The homing subroutine flow diagram

    The homing subroutine (see Figure 19) was decided upon realising that the robot uses relative

    encoders. Relative encoders do not maintain position information when power is lost which

    means the robots orientation information is also lost. Therefore there is need to define a

  • 7/26/2019 Final Project Document (Autosaved) 1

    32/97

    Page | 31

    reference point to which all robot positions are measured from. The home position is used as

    the reference point. To control the movement, the robot has to be at the home position before

    each pick or place task. Though this procedure is not time efficient, it provides an easy way of

    positioning the robot for the pick and place tasks.

    Figure 20: Robot homing sequence

    Figure 20 shows robot in its home position (all limit switches are pressed in this position) and

    the position before homing is indicated by the black frame. The shoulder joint is moved

    backwards up until the shoulder limit switch is pressed which indicates that the shoulder home

    position has been reached. On completion of the shoulder movement, the elbow is run forward

    till the elbow limit switch is pressed. For the base the program checks the status of the base

    homing switch, which is on the controller box. The base is rotated to the direction set by theuser, this is mainly due to the fact that while performing either the pick or place task, the base

    is the only joint which rotates in two directions, and, therefore, there is need for a user input to

    monitor the direction in which the base has to be rotated so that it can find the limit switch.

    Once the base has reached its home position the program checks if the gripper is holding

    anything by checking the force sensor value to find whether the force is equal or below the

  • 7/26/2019 Final Project Document (Autosaved) 1

    33/97

    Page | 32

    threshold value. If the gripper is not holding anything, the force will be lower than the threshold

    value. If it is holding anything, the algorithm checks if the picking procedure is being executed.

    If not, the gripper delays for 10s and opens so that the operator can take the picked component

    on the gripper and the homing subroutine ends. In the case that the picking procedure is being

    executed, the homing sequence ends without opening the gripper.

    4.4.3 The Pick Subroutine

    Call from

    IK

    Set_arm_1

    Is base

    direction

    forward?

    Run Base

    motor

    forward

    Yes

    Run base

    backward

    No

    Is encoder

    count ==base

    position?

    Is encoder

    count==base

    position?

    NoNo

    Run Shoulder

    motor

    forward

    Yes

    Yes

    Is encoder

    count ==

    shoulder

    position?

    No

    Run Elbow

    motor

    backward

    Is encoder

    count ==

    Elbow

    position?

    No

    Run gripper

    motor

    forward

    Is force

    sensor

    value==to

    force

    threshold

    value?

    No

    Call

    homing

    procedure

    Figure 21: The pick subroutine flow diagram

  • 7/26/2019 Final Project Document (Autosaved) 1

    34/97

    Page | 33

    The pick subroutine (see Figure 21) is called from the inverse kinematics method set_arm_1 (x,

    y, z) which takes the pick coordinates entered by the user as input and performs inverse

    kinematics calculations. The pick algorithm rotates the base in the relevant direction. The

    rotation stops once the calculated pulses from the inverse kinematics method are equal to the

    pulses counted by the MCU. On completion of the base rotation, the shoulder is moved forwardtill it reaches its required destination. On completion of the shoulder motion, the elbow is

    moved backwards till it reaches its final position. Finally the gripper is closed until the force

    sensor reads a value equal to the set threshold value of the gripping force. The pick subroutine

    calls the homing procedure once the item to be picked is held by the robot gripper.

  • 7/26/2019 Final Project Document (Autosaved) 1

    35/97

    Page | 34

    4.4.4 The Place Subroutine

    Call from

    IK

    Set_arm_2

    Is base

    direction

    forward?

    Run Base

    motor

    forward

    Yes

    Run base

    backward

    No

    Is encoder

    count ==base

    position?

    Is encoder

    count==base

    position?

    No

    Run Shoulder

    motor

    forward

    Yes

    Yes

    Is encoder

    count ==

    shoulder

    position?

    No

    Run Elbow

    motor

    backward

    Is encoder

    count ==

    Elbow

    position?

    No

    Run gripper

    motor

    backward

    Is gripper

    limit

    switch==LOW

    ?

    No

    Call Place

    homing

    procedure

    Figure 22: The place subroutine flow diagram

    The place subroutine (see Figure 22) is called by the method set_arm_2 (x, y,z) which takes the

    place positions as input and performs the inverse kinematics calculations on them. The place

    subroutine is similar to the pick subroutine, with the only difference being the gripper

    sequence. In the pick algorithm the gripper is opened before the home sequence is called by

    the robot.

  • 7/26/2019 Final Project Document (Autosaved) 1

    36/97

    Page | 35

    4.5 Operation Description

    4.5.1 Operation Sequence

    1. Switch on the power and the robots moves to home position.

    2. Press the start button.

    3. The program prompts for user input.

    4. The inverse kinematic procedure calculates the joint angles.

    5. The robots moves to the pick position with the gripper open above the object to be

    picked.

    6. The robot picks the object and returns to the home position.

    7. The robot moves to the place position.

    8. The gripper opens and places the object.

    9. The robot returns to the home position after placing is done.

    10.The program waits for the operator to press the start button again to start another pick

    and place task.

    4.5.2 Safety

    Extreme care should be taken while in the vicinity of the robot arm as the Scorbot robot

    arm is very dangerous and carelessness can result in bad injuries.

    1. Make sure the robots base is fastened to the work surface by means of at least three

    bolts, set 120 apart .Otherwise, the robot could become unstable and topple over

    during operation.

    2. Make sure the robot arm has sufficient space in which to move freely.

    3. Do not place your hands or fingers or any object within the robot arms operatingrange,

    when the power supply is on.

    4. When approaching or handling the robot, make sure the power supply switch on the

    controller back panel is shut off, because an unexpected signal may cause the robot to

    move.

    5. Do not open the controller housing.

    6. The workload should not exceed 1kg.

    7. The operator should leave the robot at home position after using it, unless there is an

    emergency which requires cutting power from the system.

  • 7/26/2019 Final Project Document (Autosaved) 1

    37/97

    Page | 36

    5 Design and Development Procedure

    5.1 Introduction

    This section of the document explains the procedure followed to attain the final design of the

    project. The parameters used for selecting the power supply are also explained in this section.

    The robot kinematics calculations are also explained in this section and the solution determines

    the robot joint angle orientation for a given input of Cartesian coordinates. The robot motor

    control method used for this project is also thoroughly covered.

    5.2 Mechanical

    5.1.2 Gear transmission mechanisms

    The gears are already installed on the robot and were designed by Eshed Robotec and the main

    purpose of this subsection is to explain the gear transmission calculations required for the

    controlling of the robot. The gear transmission ratio is calculated for the shoulder and elbow to

    determine the final resolution of the encoders which are installed directly on the DC motor

    shaft. No calculation is done for the base and gripper because the information required to

    conduct the gear ratio calculations is not supplied in the robots manual. This problem can be

    overcome by finding the relationship between the angle rotated for the base and the number

    of encoder counts required to reach that position. As for the gripper, control is achieved

    through feedback information from the gripper limit switch and the force sensor. The gripper

    stops opening when the gripper limit switch is hit and it stops closing when the required

    gripping force is attained, thus the gripper control method does not require gear information.

    Figure 23: Motor and encoder schematic

  • 7/26/2019 Final Project Document (Autosaved) 1

    38/97

    Page | 37

    The encoders are directly connected to the motor shaft (see Figure 23) so that the resolution is

    reduced by a factor similar to the gear ratio. Suppose the gear box has a gear ratio Tm, if the

    joint angle shaft rotates N times then the motor shaft rotates by:

    With the encoderSuppose the encoder outputs Fpulses per revolution of the motor shaft, then the number of

    pulses required to rotate the joint angle shaft by a single degree is proportional to:

    The resolution is the reciprocal of the number of pulses required to move the output shaft by

    one degree, thus:

    Thus the resolution is improved by a factor equal to the gear ratio. This greatly increases the

    number of encoder counts required to move the angle shaft per degree and thus improves the

    accuracy of the robot. The SCORBOT ER III has three types of gear engines within the motors

    case and each engine type has a different gear assembly mechanism. The engine types are:

    Tm = 127.7: 1 - for the base, shoulder and elbow

    Tm= 19.5: 1 - for the gripper

  • 7/26/2019 Final Project Document (Autosaved) 1

    39/97

    Page | 38

    5.1.2.1 Shoulder Transmission (Direct Transmission)

    Figure 24: Shoulder double transmission

    The shoulder uses a double transmission mechanism in which the shoulders armsare rotated

    simultaneously by the shoulders motor. The torque is transmitted to the arms through a

    hollow axle which is along the arrow labelled shoulder axle (see Figure 24). Both ends of the

    axle are fixed, this helps in keeping the shoulder stable when subjected to a load.

  • 7/26/2019 Final Project Document (Autosaved) 1

    40/97

    Page | 39

    Figure 25: Base gear transmission (www.re positorio.bib.upct.es/dspace)

    The small gear with Na= 18 teeth is installed directly on the servomotors output shaft and the

    large gear with Nb= 72 teeth is fixed to the joint of the robots shoulder . Gear A and gear B

    move in opposite directions. The motion chain formed by rotating the gear is:

    - Transmission ratio of gear A to gear B

    The transmission ratio also determines the relative rotational speeds between gear A and gear

    B. In this situation, gear A rotates times faster than gear B.

    - The speed of rotation of gear A - The speed of rotation of gear BSince the motor has its own gearbox, the total transmission ratio Tfrom the motor shaft to the

    shoulder is: The value of the total transmission ratio is required for the encoder resolution of the shoulder.

  • 7/26/2019 Final Project Document (Autosaved) 1

    41/97

    Page | 40

    5.1.2.2 Elbow Transmission (Indirect Transmission between Gears)

    The double transmission mechanism combination of the shoulder and elbow (see Figure 26)

    prevents the arm from twisting and thus increases the stability of the arm.The axles of the

    shoulder and elbow are fixed at their ends to the robot frame, this helps in preventing the

    robot arm from twisting and thus increases stability.

    Figure 26: Double transmission mechanism of shoulder and elbow

  • 7/26/2019 Final Project Document (Autosaved) 1

    42/97

    Page | 41

    The elbow works on a double indirect transmission mechanism (see Figure 27) with one double

    indirect transmission mechanism for each side.

    Figure 27: Indirect transmission between two stages (www.repositorio.bib.upct.es/dspace)

    The transmission between gears A and B causes a change of rotation direction and the

    transmission between gears C and D does not change direction because of the timing belt that

    connects them. The number of teeth N for each of the gears is:

    NA= 18

    NB= 72

    NC = 18

    ND= 18

    The transmission ratio T is a product of the relationships of all the gear stages and is calculated

    as:

    The relationship of the rpm speed between gear A and gear D is calculated as:

    Taking the elbow motors gear ratio into consideration, the total transmission ratio Tfrom the

    motor shaft is: This ratio is similar to the ratio calculated for the shoulder; this is due to the fact that thus

    .Thus the gears connected by the belt have no effect on the gear ratio calculation results.

  • 7/26/2019 Final Project Document (Autosaved) 1

    43/97

    Page | 42

    5.1.2.3 Transmission of the base joint

    The transmission of the base is a direct transmission mechanism. One gear is coupled to the

    motor output shaft and rotates with the shaft and the driven gear is coupled to the rotor body.

    The gear ratios were not supplied in the robot manual and no information could be gathered

    from both the supplier and the Scorbot robot arms support group, thus no calculations aredone for the base. An alternative approach was therefore used to position the base which

    involved calculating the number of pulse required to move the base by an angle of one degree.

    5.1.2.4 Transmission of the gripper

    The gripper fingers (see Figure 28) are moved by a smaller engine compared to other axes,

    which is attached permanently to the wrists articulation. The gripper operates on a lead screw

    mechanism, rotation of the gripper motor rotates the lead screw resulting in the opening or

    closing of the gripper. The pitch of the lead screw determines the linear distance moved by the

    gripper per revolution of the output shaft of the motor engine. Increasing the screw pitch,

    results in an increase in speed of the gripper opening and closing, but however decreases the

    resolution of the gripper fingers.

    Figure 28: Gripper Transmission (www.repositorio.bib.upct.es/dspace)

    http://www.repositorio.bib.upct.es/dspacehttp://www.repositorio.bib.upct.es/dspace
  • 7/26/2019 Final Project Document (Autosaved) 1

    44/97

    Page | 43

    5.2 Electrical

    5.2.1 Encoder Circuit Design

    Figure 29: Encoder circuit

    According to Eshed Robotec (1995: F-2), the emitting diodes are fed by a 5V power supply and a

    39 resistor in series. The resistor is however not included in the encoder (Figure 29 shows thefinal circuit with resistors added). The encoder also has two open collector outputs. Therefore

    the main purpose of the electrical design is to add a current limiting resistor for the LEDs in

    series and design a circuit to interface the collector outputs to the Arduino.

  • 7/26/2019 Final Project Document (Autosaved) 1

    45/97

    Page | 44

    Figure 30: LED circuit calculations diagram

    The value of the rated minimum current of the LEDs can be approximated since the supply

    voltage and the resistor required is specified by the manufacturer. The following parameters

    are used for the calculations:

    R = 39 Ohms

    VCC = 5V

    The voltages of the LEDs can be considered to be zero. This has an effect of reducing the

    calculated current from the actual current. The value of the calculated current can be used for

    further calculations since it will be below the rated current. The following calculation is used to

    approximate the current required by the diodes:

    Thus to prevent the diodes from blowing up, a resistor should be selected such that the current

    in the diode circuit is below 0.128A.A resistance of 100was selected because it was readily

    available.

  • 7/26/2019 Final Project Document (Autosaved) 1

    46/97

    Page | 45

    The following calculation is done to verify that the limiting current is not exceeded:

    The resulting current is below the limiting current and thus a 100 Ohm resistor can be used.

    Figure 31: Phototransistor resistance calculation

    The phototransistor (see Figure 31) behaves like a switch. Its terminals open when exposed to

    light and the terminals are closed when it is not exposed to light. The output pin of the

    phototransistor is interfaced with the MCU through a pull-up resistor. The pull-up resistor

    chosen should satisfy these conditions (Ronzo, 2012):

    1. When the button is pressed, the input pin is pulled low. The value of the resistor

    controls how much current you want to flow from 5V through the resistor R1, through

    the button, and then to ground.

    2. When the button is not pressed, the input pin is pulled high. The value of the pull -up

    resistor controls the voltage on the input pin.

  • 7/26/2019 Final Project Document (Autosaved) 1

    47/97

    Page | 46

    The general rule for condition 2 is to use a pull-up resistor (R1) shown in Figure 31 that is an

    order of magnitude (1/10th) less than the input impedance (R2) of the input pin (Ronzo,

    2012).The maximum current allowed for the arduino IO pins is 40mA and these pins have an

    input impedance which varies from 100k-1M.The Arduino Mega detects a voltage as high if

    it is 3V or more, thus the selected resistor should pull-up the voltage to at least 3V.Thereforewith these guidelines R1 can be calculated as:

    There is need to verify the amount of current drawn by the 10k resistor and this is calculated

    using ohms law as:

    The calculated current is less than 40mA and it is below the maximum allowable current and

    thus the selected resistance value can be used. The voltage on the input pin of the MCU when

    this selected resistor is used is:

    This value can be detected as a high input by the MCU since it is greater than 3V.A 10k

    resistor satisfies the selection parameters and was implemented in the circuit.

    The next phase involved implementing the resistor circuit on a breadboard. The circuit was

    tested on an oscilloscope to verify if the correct pulses were being generated as the motor was

    being run. Finally the circuit was soldered for all the four axes and its performance was tested

    on an oscilloscope. The resulting pulses were perfect, fluctuating from roughly 0V -5V as

    required. The pulses for the two channels had a 90 degrees phase shift as expected (see Figure

    32).The pictures of the experimental setup are in Appendix C-1.

  • 7/26/2019 Final Project Document (Autosaved) 1

    48/97

    Page | 47

    Figure 32: Encoder output as seen from oscilloscope

    5.2.2 Limit switch and Pushbutton circuit design

    Figure 33: Limit switch pull-up resistance selection

    The switches and pushbuttons are implemented with a stand pull-up resistance of R1=10k.

    The switch output to the MCU is pulled up to 5V when the switch is open and is pulled to

  • 7/26/2019 Final Project Document (Autosaved) 1

    49/97

    Page | 48

    ground when the switch is closed. The calculation to verify the selection of the pull-up resistor

    is similar to the calculation done for the phototransistor. The only difference between the two

    circuits is that the phototransistor in Figure 31 is replaced by a switch in Figure 33.The circuit

    performance was analysed in Multisim and the digital multimeter readings gave the expected

    results (see Figure 34). The open switch gave an output voltage of approximately 5V while theclosed switch exhibited zero voltage output.

    Figure 34: Multisim simulation of the pull-up switch circuit

    The circuit for all switches was soldered on a veroboard and was tested by read it through a

    digital input pin on the Arduino MCU. The results were displayed on the serial monitor, which is

    a HyperTerminal. An output of logic zero was observed when the switches were closed and a

    logic one was observed when the switches were open (see Figure 35).

  • 7/26/2019 Final Project Document (Autosaved) 1

    50/97

    Page | 49

    Figure 35: Switch test results displayed through the Arduino serial monitor

    5.2.3 Force Sensor Circuit design

    Figure 36: Recommended circuit of the force sensor (Interlink, 2012: 18)

    Figure 36 shows the suggested electrical interface of Force sensing resistors according to

    Interlink (2012: 18).The output voltage (VOUT) and the input force variation for different

    voltage divider resistance values (RM) is shown in figure 37.The curve is plotted for an input

    force which varies between 0-1kg.

  • 7/26/2019 Final Project Document (Autosaved) 1

    51/97

    Page | 50

    Figure 37: Force vs Voltage characteristic for the A401 sensor

    The value of 100k was chosen for the voltage divider circuit. This value was chosen because

    the load which was being picked by the robot had a mass of 170g.The 100k resistor has the

    largest output voltage range which stretches from 0V-5V and it also has the most sensitive to

    changes in the force values in the 0g-200g domain. The output voltage is calculated using the

    voltage divider equation.

    Voutis connected to the analog pin of the Arduino MCU.The Analog to Digital Converter (ADC)

    which is a peripheral device on the Arduino MCU converts the voltage value from the analog

    pin to a value that can be interpreted by the MCU.The Arduino MCU has a 10bit ADC which

    corresponds to a range of:

    This range corresponds to values between 0-1023.The ADC value on an Arduino which is a 5V

    system, is calculated as:

  • 7/26/2019 Final Project Document (Autosaved) 1

    52/97

    Page | 51

    5.2.4 Power Supply unit selection

    The equation is used to calculate the total power required by the motors; the otherelectrical circuit components require a 5V supply and are powered by the Arduino MCU which

    has its own 5V power supply. The parameters used to select the power supply are:

    The motor voltage requirements = 5V DC

    The motor maximum current = 2A

    The number of motors which require power is four and a worst case scenario in which all the

    motors run at once is used to calculate the total power. In practice, such a case will never

    happen since the motors run sequentially one after the other. The total amount of power and

    current required from the power supply, in a worst case scenario, is:

    Thus, the minimum power supply power required for running the motors is 96W and the total

    current drawn is 8A. Power supplies from various suppliers were considered (see Table 3).

    Table 3: Power supplies considered

    Manufacturer Specifications Supplier Cost

    Mean Well 230V ac to 12V dc

    18 A

    Second hand

    shop

    R 100

    RS 230V ac to 12V dc

    18 A

    RS components R672.95

    Hobbytronics 230V ac to 24V dc

    10 A

    Electronics 123 R132.95

    The Mean Well power supply which had the cheapest price, but still retained the required

    functionality, was chosen.

    5.3 Robot Kinematics

    5.3.1 Denavit Hartenberg Forward and Inverse Kinematics

    The inverse kinematics technique is used to calculate the joint angle parameters for a given end

    effector orientation. The pick and place positions of the robot gripper are described in terms of

    a fixed Cartesian coordinate system. Therefore the main purpose of this technique is to map

    the Cartesian coordinates of the gripper through a function which outputs the angles to which

    the joints of the robot arm must be rotated. The coordinate frame assignment of the Scorbot

  • 7/26/2019 Final Project Document (Autosaved) 1

    53/97

    Page | 52

    robot arm with respect to the D-H rules is depicted in Figure 38(Deshpande & George, 2012:

    479).

    Figure 38: The Denavit-Hartenberg frame assignment of the Scorbot ER-III (Deshpande & George, 2012:479)

    The reference frames are assigned according to the following rules (Spong et al, 2007:70):

    The -axis is orthogonal to the axes and .

    The -axis also intersects the and axes.

    The intersection point of and marks the origin of joint .

    can be found using the right hand rule of Cartesian coordinates.

    The transformation is described by the DH parameters:

    : offset along previous to the common normal.

    : angle about previous , from old to new .

    : Length of the common normal.

    : Angle about common normal, from old axis to new axis.

  • 7/26/2019 Final Project Document (Autosaved) 1

    54/97

    Page | 53

    The D-H parameters are represented in a table (see Table 4) assigning the specific

    parameters for the Scorbot ER-III.The parameters are substituted in to the D-H matrices

    which the end effector position for a given robot arm orientation. In other words, the

    transformation is a forward kinematics function. The forward kinematics solution results in

    a set of equations, which express the end effectors Cartesian coordinates in terms of the D-H parameters. The Inverse kinematics involves solving the equations so that the joint angles

    can be calculated.

    Table 4: Scorbot ER-III D-H parameters

    The transformation matrix from joint i to joint i+1 is shown in Figure 39.

    Figure 39: Scorbot transformation matrix (Deshpande& George, 2012: 479)

    And Si=sin i, Ci= cos i, Si=sin i, Ci=cos i, Sijk=sin (i+ j+ k), Cijk=sin (i+ j+ k)

    Multiplying alli-1

    Tifor i = 1 to 5 (0T1,

    1T2,

    2T3,

    3T4,

    4T5), results in the total transformation from

    0

    T5.The total transformation matrix is shown in Figure 39.

  • 7/26/2019 Final Project Document (Autosaved) 1

    55/97

    Page | 54

    Figure 40: The total transformation matrix (Deshpande & George, 2012: 479)

    The end effector transformation matrix (Te) is expressed as:

    Figure 41: The end effector transformation matrix (Deshpande & George, 2012: 479)

    For the Inverse kinematics problem, the end effector position is known and therefore the all the

    entries of Te are known. The inverse kinematics problem is basically the solution to theequation:

    0T5= Te

    This results in the following system of equations shown in Figure 42:

    Figure 42: Inverse kinematics equations (Deshpande & George, 2012:479)

  • 7/26/2019 Final Project Document (Autosaved) 1

    56/97

    Page | 55

    This set of equations is not easy to solve and therefore a geometric solution to the problem is

    followed to determine the angle parameters for the robot arm.

    5.3.2 Geometric approach to inverse kinematics

    Figure 43: Robot representation for geometric analysis

    Figure 43 shows the robot arm and the Cartesian frame (i.e. the xyz frame) from which the pick and

    place positions are measured from. In Figure 44 and Figure 45 the robot arm is removed so that the

    shapes used for the geometric calculations are easy to view.There are two scenarios presented by

    the geometric approach, let:

  • 7/26/2019 Final Project Document (Autosaved) 1

    57/97

    Page | 56

    For s > 0 (i.e. the wrist joint is higher than the shoulder joint along the Z-axis), the equation of

    the geometric problem is derived as:

    Figure 44: Inverse kinematics geometric approach

    The elbow angle is calculated by applying the cosine rule to the triangle ABC, thus:

  • 7/26/2019 Final Project Document (Autosaved) 1

    58/97

    Page | 57

    From the definition of the sine rule, angles A and B can be calculated as:

    Therefore:

    For the second scenario s < 0, the orientation of the triangle ABC (see Figure 45) is changed and

    it only affects the solution for due to the change in position of angle d. In this end effectororientation, the wrist joint is lower than the shoulder joint along the positive Z-axis.

    Figure 45: Geometric approach for the second scenario

    For this orientation, the value of becomes: ( )

  • 7/26/2019 Final Project Document (Autosaved) 1

    59/97

    Page | 58

    Either formula can be used for the scenario in which S = 0. On analysis of the movement of the

    Scorbot robot arm, it is observed that the robots ulna moves horizontally when the humerus is

    in motion. The motion of the ulna is always along the direction of E (see Figure 46).Thus, the

    elbow joint angle is always changing whenever the shoulder is in motion. Thus, for motion

    control the value calculated for will not be the actual angle the ulna has to be rotated.

    Figure 46: Ulna motion for the Scorbot robot arm

    The final position of the ulna is from the humerus axis (see Figure 46). After the movementof the humerus about the shoulder angle, the ulna will have moved an angle of a. Therefore,

    for position control, the controller should send commands to move the elbow joint by an angle

    of where angle ais given by:

    5.3.4 Sample calculations

    Suppose it is required to move the end effector to the point the jointangle parameters are calculated by the MCU as:

    Therefore the second scenario of the inverse kinematics problem should be solved.

    =

  • 7/26/2019 Final Project Document (Autosaved) 1

    60/97

    Page | 59

    ( ) ( ) ( )

    Thus the inverse kinematics function maps the point to .From the elbow joint motion trajectory analysed, itis required that the control algorithm should only move the joint by: The base and shoulder are rotated by and respectively to attain the desired end effectorposition for the pick and place tasks.

    5.4 Position Control of the robot arm

    5.4.1 Position Control System

    Figure 47: Joint control system block

    The position control system applied in this project is illustrated in Figure 47.The solution from

    the inverse kinematics is converted into pulses through calculations which will described later.

  • 7/26/2019 Final Project Document (Autosaved) 1

    61/97

    Page | 60

    The number of pulses required to reach a certain angle is stored as a variable for the desired

    position. The MCU drives the joint motor and the encoder count is monitored while the motor

    is running. The joint motor is driven until the difference between the encoder count and the

    number of pulses required to reach the position is zero. The MCU sends commands to the H-

    Bridge driver to stop the motor when the difference is zero.

    5.4.2 Optical Encoder decoding

    Figure 48: Output pulses for channels A and B (National Instruments, 2001)

    The optical encoder of the Scorbot robot arm outputs two pulses positioned 90 degrees out of

    phase (see Figure 48).These two channels show both the position and direction in which the

    joint motors rotate. For example if A leads B then the motor is rotating in a clockwise direction

    and if B leads A, then the motor is rotating in an anti-clockwise direction. The position can be

    monitored by counting the number of pulses and the direction can be monitored by checking

    the relative phase of channels A and B.

    Figure 49: X1 decoding scheme (National Instruments: 2001)

    The X1 decoding scheme (see Figure 49) is used to control the position of the joint angles of the

    robot arm. Angular position is determined by the number of falling or rising edges counted by

  • 7/26/2019 Final Project Document (Autosaved) 1

    62/97

    Page | 61

    the MCU in order to attain that angle. The sequence 765(see figure 49) in which channel B leads

    channel A was used to determine the number of counts required to reach a position. The MCU

    uses an interrupt to on every falling edge of A and checks B to detect the direction of rotation.

    If Ch B is high on the falling edge of Ch A, the count is incremented and if B is low the count is

    decremented. The count is incremented until the desired number of pulses required is reached.

    The Inverse kinematics procedure calculates the joint angle parameters for a given angular

    position. For the position control of the robot arm, the algorithm implemented takes the angle

    as input and calculates the number of pulses required to rotate to that given angle. The formula

    implemented to calculate the number of pulses required to move one degree is:

    Where:

    Number of pulses required to move by one degree

    Encoding type, which is 1 because X1 decoding is used for controlling all the joint motors. Number of pulses generated per shaft revolution (which is equal to 6 for all joints exceptthe gripper)

    Gear transmission ratio from the motor driving gear to the joints driven gear.5.4.4 Calibration Procedure

    Due to the fact that measurements taken in labs are not precise, there is need to take multiple

    measurements of the dependent variable at every value of the independent variable. A

    calibration procedure was done so that the relationship between the number of encoder

    counts required to reach a certain angle can be expressed as a function of the desired output

    angle. The number of pulses is the independent variable(y) that was manipulated and the

    measured angle was the dependant variable(x) that was recorded for each joint.

    For each pulse value three angle recordings were taken, the mean value of these readings was

    calculated and this mean value was plotted as a single point on the calibration curve. The mean

    value was calculated using the AVERAGEfunction in using Microsoft Excel and it is equal to:

    The standard error was used to express the uncertainty of the calculated mean values of the

    angles which are used to plot the calibration curve.

  • 7/26/2019 Final Project Document (Autosaved) 1

    63/97

    Page | 62

    The standard error is calculated from the standard deviation as:

    The standard error represents the confidence range in which the mean value represents the

    true value of the measured angle. The standard error is expressed visually through errors bars

    which are shown in the calibration curves (see Figure 51).A wide error bar represents a low

    level of confidence in the representation of the true value by the mean value(Labwrite,2012).

    The linear regression method is used to express the number of pulses as a linear function of the

    angle required to move the joint. The linear function is of the form:

    Where M is the gradient of the resulting curve, and c is the y-intercept. The mean values for

    each recording were used to plot the calibration curve.

  • 7/26/2019 Final Project Document (Autosaved) 1

    64/97

    Page | 63

    5.4.4 Base Position Control

    5.4.4.1 Base Calibration

    Figure 50: Base rotation

    The base control is achieved through a calibration process which was conducted at 60% duty

    cycle because the experimental results (see section 6.1) showed that the base had the least

    error when the base motor was driven by a PWM signal with 60% duty cycle. The methodology

    used involved keeping the numbers of pulses sent to the MCU as the independent variable.

    Calibration was done at 100 pulse intervals for both clockwise and anticlockwise rotation of thebase since the base is controlled from the center. The actual angles moved by the base were

    measured using a protractor. The calibration procedure was the only method implemented for

    the control of the base because no information relating to the gear mechanism was found. The

    table of results can be found in Appendix C-2.Figure 37 shows the results for the clockwise

    calibration.

  • 7/26/2019 Final Project Document (Autosaved) 1

    65/97

    Page | 64

    Figure 51: Base clockwise rotation calibration curve

    The calibration was modelled as a linear pattern. The results had a great correlation coefficient

    of 0.9945; this value is close to 1 which indicates that the recorded data closely resembles a

    linear model. The maximum standard error recorded is +/- 3.4 degrees which corresponds to1000 pulses this can be seen visually by the widest error bar at 1000 pulses(see Figure 51). The

    resulting equation was solved forxwhich represents the number of pulses.

    From the inverse kinematics sample calculations, to move the base 26.565 degrees towards the

    positive y direction, the number of pulses required is:

  • 7/26/2019 Final Project Document (Autosaved) 1

    66/97

    Page | 65

    The results of the base anticlockwise calibration showed a good correlation coefficient of 0.992,

    this value is close to 1 which indicates that the recorded data closely resembles a linear model.

    The maximum standard error recorded