Development of a MATLAB Toolbox for 3-PRS Parallel Robot

Size: px
Start display at page:

Download "Development of a MATLAB Toolbox for 3-PRS Parallel Robot"

Transcription

1 International Journal of Hybrid Information echnology, pp Development of a MALAB oolbox for 3-PRS Parallel Robot Guoqiang Chen and Jianli Kang * Henan Polytechnic University, China jz97cgq@sina.com, kangjl@hpu.edu.cn Abstract Aiming at one kind of 3-PRS parallel robot, the study develops a toolbox in MALAB. he toolbox includes functions for forward kinematics, inverse kinematics, velocity kinematics, error analysis, schematic representation, and so on. he architecture of the 3-PRS robot is introduced firstly. he instructions of the functions, developing procedure and main algorithms are presented secondly. he toolbox encapsulates complicated mathematical formulas into the single function and provides standard inputs and outputs, which improves the reliability and makes it easy to use. Finally, an example calls the toolbox function, and verifies its correctness, reliability and convenience. Keywords: 3-PRS parallel robot, toolbox, forward kinematics, inverse kinematics. Introduction As an important branch of the industrial robot, the parallel robot has many advantages, such as high stiffness, high accuracy, little cumulate error, large load carrying capacity and compact structure [-7]. It has gained wide applications in all kinds of fields and attracted plenty of study. he 3-PRS parallel mechanism is very typical in the parallel robot family [4]. here are many complicated mathematical formulas in analysis on degrees of freedom, working envelope, kinematics, speed, acceleration, accuracy, and so on [8-8]. Especially, the trigonometric function computation, nonlinear equations and complex matrix make design and analysis tedious and discouraging [, 3-5, 7-8]. he engineering software MALAB has powerful performance in numerical computation, symbolic operation and graphical representation, so it is an efficient tool for the robot research [9]. he aim of this paper is to present a computer-aided analysis toolbox developed in MALAB for one kind of 3-PRS parallel robot, and give key algorithms.. Architecture of 3-PRS Parallel Robot he schematic representation of the 3-PRS parallel robot is shown in Figure [, 3-5,7-9]. he robot is composed of a moving platform, three limbs, three vertical rails and a fixed base. hree vertical rails vertically link to the base B B B. Moreover, B B B form an equilateral 3 3 triangle that lies on a circle with the radius R.he axis of the revolute pair R i for i, and 3 is perpendicular to the prismatic pair. Each limb L i for i, and 3 with the length of l i connects the corresponding rail by a prismatic pair R i. he moving platform and three limbs are connected by three spherical pairs b, b and b 3. hree spherical pairs form an equilateral triangle that lies on a circle with the radius r. he cutter with the length of h is placed at the *Corresponding Author: Jianli Kang is the corresponding author. kangjl@hpu.edu.cn his work is supported by Scientific and echnological Project of Henan Province of China with grant No ISSN: IJHI Copyright c 4 SERSC

2 International Journal of Hybrid Information echnology center of the moving platform. he feed of the prismatic pair is given as H. Angles for i i i, and 3 are defined from the vertical rail to its corresponding limb L i. As shown in Figure, a fixed Cartesian reference coordinate system OXYZ is located at the center O of the base B B B. X-axis and Y-axis are in the base plane B 3 B B, X-axis points in the direction of O 3 B, and Z-axis is normal to the base plane and points upward. A moving coordinate frame o xyz is located at the cutter point o. he xy plane is parallel to the moving platform b b b, x- 3 axis points in the direction of C b, and z-axis is normal to the moving platform. he position and orientation of the cutter can be described using the coordinates x, y, z of the cutter o o l o o l o o l point and Euler angles, and rotating about Z, Y and X axes of the fixed system. he 3- PRS parallel robot possesses 3- DOF that are rotation about the Z-axis and about the Y- axis, and a translational motion z along the Z-axis [9]. hree parasitic motions include one rotation, one translational motion x about the X-axis, and one translational motion y about the Y-axis. he three parasitic motions, x and y can be expressed using the three independent motions, and z. R 3 H 3 3 B 3 L 3 R L B b 3 b o z C Z O y Y b h L x B R H X Figure. Schematic Representation of the 3-PRS Parallel Robot 3. oolbox Development in MALAB All toolbox function names begin with the prefixion 'PRS_'. In the toolbox functions, the parameters A, B, G, R, r, h, X and Y represent,,, R, r, h, x and y, respectively. H is a -by-3 vector that represents [ H, H, H ]. H is a -by-3 vector that represents [ 3,, ]. B, B, B3, R, R, R3, b, b and b3 are -by-3 vectors of the corresponding points 3 coordinates, respectively. R R 3 b b 3 Y O r b R X R 4 Copyright c 4 SERSC

3 International Journal of Hybrid Information echnology 3.. Function for Homogeneous ransformation Matrix = PRS_ran (A, B, G, P) returns a 3-by-4 array that represents the homogeneous transformation matrix computed using Equation () from o xyz to OXYZ. he input parameter P is the vector x y z. o o l o o l o o l C C C S S x S S C C S S S S C C S C y C S C S S C S S S C C C z where S, S, S, C, C and C represent s in, sin, sin, co s, co s and cos respectively. 3.. Function for Euler Angle G = PRS_ABG (A, B) returns the Euler angle that can be expressed by the other two angles and using Equation (). sin sin arctan c o s c o s 3.3. Function for Parasitic Motions x and y [X, Y]= PRS_XY (A, B, G, r, h) returns the parasitic motions x computed using Equation (3). r x c o s c o s sin sin sin c o s c o s h sin y h sin c o s r sin sin c o s r c o s sin 3.4. Function for Coordinates of B, B and B3 o o l o o l o o l () () and y that can be [B, B, B3]= PRS_BiXYZ (R) returns the coordinate vector of B, B and B3 using the following equation system. B = R 3 B = R R 3 B = R - R 3 (3) (4) 3.5. Function for Coordinates of R, R and R3 [R, R, R3]= PRS_RiXYZ (H, R) returns the coordinate vector of R, R and R3 using the following equation. Copyright c 4 SERSC 43

4 International Journal of Hybrid Information echnology R R H 3 R R R H 3 R R R H 3 3 (5) 3.6. Function for Coordinates of b, b and b3 [b, b, b3] = PRS_ForKinbi(H, H,PofPRS) returns the coordinate vector of b, b and b3. PofPRS is a vector including 4 elements that represent R, l, l and l 3. he coordinate vector of b, b and b3 in the system o xyz can be computed using Equation (6). Combined with the transformation matrix, the coordinate vector in the system OXYZ can be gotten. b r h 3 b r r h 3 b r r h Function for Angles between Vertical Rails and Corresponding Limbs [H, Flag]= PRS_ForKinH (H, PofPRS, H) computes three feeds and angles using the optimal iteration algorithm based on based on Equation (7). PofPRS is a -by-5 vector that represent r, R, l, l and l 3. he initial iteration value H is a vector including 3 elements, and has heavy effect on the rationality of the solution Function for the Direction Vector of the z-axis b b b b b b 3 r (7) 3 3 Vz= PRS_zVectorFrombbb3 (b, b, b3) returns the direction vector of the z-axis. he direction vector can be computed using the following formula. e 3 b b b b b b b b b b b b b b b b b b b b b b b b (6) (8) 44 Copyright c 4 SERSC

5 International Journal of Hybrid Information echnology 3.9. Function for the Coordinates of the Cutter Point [Xool, Yool, Zool]= PRS_XYZFrombbb3(b,b,b3,h,dx,dy) returns the cutter point coordinates x, y, z. dx and dy are the offsets x and y along x-axis and y-axis o o l o o l o o l between the center C of the equilateral triangle and the perpendicular projection point C of the cutter point in the equilateral triangle plane, shown in Figure. he algorithm can be expressed as follows. b3 D b x E C F y C y x x, y, z Figure. Algorithm Diagram for Function PRS_XYZFrombbb3 he coordinates x, y, z C C C of the center C of the equilateral triangle bbb3 can be expressed as x y z C C C x x x 3 b b b 3 y y y 3 b b b 3 z z z 3 b b b 3 Based on the coordinates of b and b, the direction vector computed. he parameter equation for the y-axis line is he corresponding t of the point E is x x m t C y y n t C z z p t C t y m n p b m, n, p (9) of the y-axis can be () () he coordinates x, y, z E E E of E can be computed. Likewise, the coordinates of bb3 center D can be gotten, the direction vector of the x-axis can be computed, and the coordinates Copyright c 4 SERSC 45

6 International Journal of Hybrid Information echnology x y z of the point F can be gotten. Based on coordinates of points E and F, the center,, F F F coordinates of the parallelogram C F C E can be computed, and coordinates the point C are x, y, z C C C of x x x x y y y y z z z z C E F C C E F C C E F C he function PRS_zVectorFrombbb3 is called to compute the direction vector of the line that the cutter resides. Likewise, x, y, z can be computed. o o l o o l o o l 3.. Function for hree Euler Angles from the Direction Vector of the Cutter [A, B, G]= PRS_VectorOfoolABG(VectorOfool) returns Euler angles. he input parameter VectorOfool is a vector including three elements that represents the direction of the cutter. he 9 upper-left elements in the transform matrix form the direction cosine matrix from o xyz to OXYZ. he unit vectors of the three coordinate axes of OXYZ are E [,, ], E [,, ] and E 3 [,,], while the three unit vectors of o xyz are e, e and e 3. he direction cosine matrix D can be expressed as E e E e E e 3 D E e E e E e 3 E e E e E e he unit vector e 3 is the utilization one of VectorOfool. he matrix elements in the third row and third row of D can be computed. he Euler angles and are computed using Equation () and (), then the Euler angle is gotten by calling the function PRS_ABG. 3.. Function for the Inverse Kinematics [H, H] = PRS_BacKin (A, B, Z, PofPRS) returns three feeds and three angles. PofPRS is a vector including 6 elements that represent r, R, l, l, l 3 and h. he initial iteration value H is a vector including 3 elements, and has heavy effect on the rationality of the solution. he Euler angle is computed using PRS_ABG, and the transformation matrix is computed using PRS_ran. he coordinates of b, b and b3 in the system o xyz can be expressed as [ x, y, z,] b i b i b i i,, 3, and the corresponding coordinates in the system OXYZ can be computed using the transformation matrix. he feeds of the three prismatic pairs H i,, 3 are i () (3) (i=,, 3) (4) H Z Z l X X Y Y i R i b i i R i b i R i b i where Z is the Z coordinate of R R i i, l i is the length of limb L i, X and X R i b i are the X coordinates of R i and b i respectively, and Y R i and Y b i are Y coordinates of R i and b i respectively. 46 Copyright c 4 SERSC

7 International Journal of Hybrid Information echnology 3.. Function for all Solutions of Angles Using Monte Carlo Simulation [H,N]= PRS_ForKinAllH (H, PofPRS, HMin, HMax, K, M, Error) returns all solutions of three angles between vertical rails and corresponding limbs using Monte Carlo simulation. he return value N is the number of the solutions. he input parameter PofPRS has the same meaning as the function PRS_BacKin, [HMin, HMax] is the interval where the solution resides, K is the number of Monte Carlo sampling, and M is the number of the possible solutions. he solutions are regarded as one if the absolute value of their difference is no more than the limiting error Error. he return number of the solutions N is no more than the set number M Function for the Position and Orientation Error Error= PRS_ManError (A, B, Z, PofPRS, EPofPRS) returns the position and orientation error. he return value Error is a vector including 6 elements that represent the errors of the three Euler angles and position coordinates. he input parameter PofPRS has the same meaning as the function PRS_BacKin. EPofPRS is a vector including elements that represent moving platform radius error r, fixing base radius error R, three limb-length-errors l, l, l, cutter length error h, three feeds errors H, H, H, offsets 3 3 x and y. he computation procedure is as follows. Step : hree feeds H and three angles H are computed using [H, H]= PRS_BacKin (A, B, Z, PofPRS). Step : he three angles are computed again using [H, Flag]= PRS_ForKinH (H+EPofPRS(7:9), PofRobot(:5)+EPofPRS(:5), H). Step 3: he three-dimensional coordinates of b, b and b3 are computed using [b, b, b3]= PRS_ForKinbi(H+EPofPRS(7:9), H, PofPRS(:5)+ EPofPRS(:5)). Step 4: he direction vector of the z-axis is computed using Vz= PRS_zVectorFrombbb3 (b, b, b3). Step 5: hree Euler angles A, B and G are computed using [A, B, G]= PRS_VectorOfoolABG (-Vz). Step 6: he coordinates x, y, z o o l o o l o o l are computed using [Xool, Yool, Zool] = PRS_XYZFrombbb3 (b, b, b3, EPofPRS(6), EPofPRS(), EPofPRS()). Step 7: he error Error is computed using the actual and nominal values Function for the Jacobian Matrix Jacobian = PRS_ Jacobian (A, B, Z, PofPRS, Flag) computes the Jacobian matrix according to the position and orientation, and the structure parameter. he input parameter PofPRS has the same meaning as the function PRS_BacKin. If Flag is, the function returns the Jacobian matrix; else, the inverse Jacobian matrix. he return value Jacobian is a 3-by-3 matrix. he 3-PRS parallel robot possesses 3- DOF, and z. Based on the Equation () and (4), three feeds are functions of, and z. he, and z are functions of the time t, and can be expressed as ( t ), ( t ) and Z ( t ). So Equation (4) can be expressed as So (5) H ( t ) F ( t ), ( t ), Z ( t ) i i Copyright c 4 SERSC 47

8 International Journal of Hybrid Information echnology where the Jacobian matrix J is dh dh d H d d d 3 Z J d t d t d t d t d t d t (6) H H H Z H H H J Z H H H Z If J has full rank, the inverse Jacobian matrix can be computed. Because of the complexity of Equations (5) to (7), the Jacobian matrix function jacobian (f, v) can be used directly Function for the Acceleration Computation ah = PRS_ Acceleration (A, B, Z,VABX, aabx, PofPRS) computes the acceleration of three feeds. PofPRS has the same meaning as the function PRS_BacKin. VABX and aabx are the velocity and acceleration vectors of the cutter direction and position, and each includes 3 elements. he return value ah is a vector including 3 elements representing the acceleration of three feeds. he transmission relationship can be gotten through differentiation using Equation (6) Function for the Structure Diagram Drawing PRS_ Plot(B,B,B3,R,R,R3,b,b,b3) plots the scheme of the 3-PRS robot. he function PRS_XYZFrombbb3 is called to compute the coordinates of the cutter point, and the MALAB function plot3 is used to draw the scheme. 4. Example Result and Discussion he structure parameters of a 3-PRS parallel robot are as follows. l l l 3 7, R 35 and h 8. he trajectory path of the cutter point is the intersection of the spherical surface and the plane z z, and the cutter is always perpendicular to the spherical surface. he trajectory path of the cutter point can also be expressed as x R s R z s c o s t y R s R z s s in t z z ( t 3 6 ) (7) r, he direction vector of the cutter is x, y, z, and the direction vector of the z-axis is x, y, z. he toolbox developed can be used to analyze the characteristics. If R s, z 6 and t 6, the computation procedure and key codes in MALAB are as follows. >> drsz=sqrt(*-(-6)*(-6)); 48 Copyright c 4 SERSC

9 International Journal of Hybrid Information echnology >> x=drsz*cos(pi/3); y=drsz*sin(pi/3); % Prepare parameters >> [A,B,G]= PRS_VectorOfoolABG(-[x,y,6]) ; % Compute three Euler angles >> [H,H]= PRS_BacKin(A,B,6,[,35,7,7,7,8]); % Compute feeds and angles >> [R,R,R3]= PRS_RiXYZ(H,35); % Compute coordinates >> [b,b,b3]= PRS_ForKinbi(H, H,[35,7,7,7]); % Compute coordinates >> [B,B,B3]= PRS_BiXYZ(35); %Compute coordinates >> PRS_Plot(B,B,B3,R,R,R3,b,b,b3,8); % Plots the scheme he feed vector of the three prismatic pairs is H=[ , , ], the three angles vector between vertical rails and corresponding limbs is H =[.359,.359,.649], and the scheme of the robot is is shown in Figure 3. 5 Z 5 Y Figure 3. Scheme of the Robot Position and Orientation for Position and Orientation he parameter t is made discrete over the interval [, 36 ). Each discretization value is computed, and the result is shown in Figure 3. PRS_BacKin is used for Figure 4 (a), PRS_XY for Figure 4 (b), and PRS_ManError for Figure 4(c) and (d). he error vector of the parameters is [.68,.77,.798,.5, -.76, -.566, -.636, -.98, -.788,.3,.878] in Figure 4(c) and (d). he three position-coordinates errors and three Euler angles errors differ greatly in value although the error source is same, which demonstrates that the position and orientation has tremendous effect on the error sensitivity. he translational motion of the 3-PRS robot possesses is only one z along the Z-axis, and it has two parasitic motions x and y, as shown in Figure 4(b). An X-Y table is needed to compensate the parasitic motions x and y, and the compensations Xp and Yp are shown in Figure 4 (b). X Copyright c 4 SERSC 49

10 International Journal of Hybrid Information echnology H H H H3 4 X Y Xp Yp t t a) Feeds of hree Prismatic Pairs b) Parasitic Motions and Compensations 5 x t t c) hree Euler Angles Errors d) Position Errors 5. Conclusions Figure 4. Computing Results of the Example A toolbox for the 3-PRS parallel robot is developed in MALAB and key algorithms are given. he toolbox includes 6 functions for forward kinematics, inverse kinematics, velocity kinematics, error analysis, schematic representation of the robot, and so on. Finally, an example calls the toolbox function, and verifies its correctness, reliability and convenience. he toolbox is very useful for design and analysis of the 3-PRS robot characteristic. he developed toolbox and its application have several advantages. he toolbox encapsulates complicated mathematical formulas into the single function and provides standard inputs and outputs, which improves the reliability and makes it easy to use. he functions are saved as m-files and all file names end with the extension '.m', so it is helpful and almost necessary for the user to modify the codes for expansion. However, it should be noticed that the 3-PRS robot can be classified into four categories including seven kinds according to limb arrangements as discussed in [9]. Based on the toolbox here, the function for the other kinds can be extended. Acknowledgements his work is supported by Scientific and echnological Project of Henan Province of China with grant No he authors would like to thank the anonymous reviewers for their valuable work Xool Yool Zool 4 Copyright c 4 SERSC

11 International Journal of Hybrid Information echnology References [] W. Liu and S. Chang, Study on structural design of a parallel robot and applications in automobiles, Machinery Design & Manufacture, no. 6, (), pp [] Z. Huang, heory of parallel robot mechanism, Anniversary of Mechanical Science Fundamental Study. Edited by. Y. Lei, Wuhan China: Wuhan University of echnology Press, (7). [3] J. Zhao, Research on the accuracy theory and the measurement device of serial-parallel machine tools, Dotoral dissertation, Wuhan China: Huazhong University of Science and echnology, (). [4] X. Liu, C. Wu, J. Wang and I. BONEV, Attitude description method of [PP]S type parallel robotic mechanisms, Chinese Journal of Mechanical Engineering, vol. 44, no., (8), pp [5] M. S. sai and W. H. Yuan, Dynamic modeling and decentralized control of a 3 PRS parallel mechanism based on constrained robotic analysis, Journal of Intelligent and Robotic Systems: heory and Applications, vol. 63, no. 3-4, (), pp [6] C. Gong, J. Xiong and C. Huang, Kinematics and dynamics simulation of Delta parallel robot, Manufacturing Automation, vol. 35, no. 3, (3), pp. 5-7&4. [7] G. Abbasnejad, S. Zarkandi and M. Imani, Forward kinematics analysis of a 3-PRS parallel manipulator, World Academy of Science, Engineering and echnology, vol. 37, () January, pp [8] M. S. sai,. N. Shiau, Y. J. sai and. H. Chang, Direct kinematic analysis of a 3-PRS parallel mechanism, Mechanism and Machine heory, vol. 38, no., (3), pp [9] Q. Li, Z. Chen, Q. Chen, C. Wu and X. Hu, Parasitic motion comparison of 3-PRS parallel mechanism with different limb arrangements, Robotics and Computer-Integrated Manufacturing, vol. 7, no., (), pp [] J. Yu, Y. Hu, S. Bi, G. Zong and W. Zhao, Kinematics feature analysis of a 3-DOF compliant mechanism for micro manipulation, Chinese Journal of Mechanical Engineering, vol. 7, no., (4), pp [] J. A. Carretero, R. P. Podhorodeski, M. A. Nahon and C. M. Gosselin, Kinematic analysis and optimization of a new three degree-of-freedom spatial parallel manipulator, Journal of Mechanical Design, ransactions of the ASME, vol., no., (), pp [] P. Huang, J. Wang, L. Wang and J. Qian, Dimensional synthesis for 3-PRS mechanism based on identifiability performance, Chinese Journal of Mechanical Engineering, vol. 5, no., (), pp [3] K. H. Hunt, Structural kinematics of in-parallel-actuated robot-arms, Journal of Mechanisms, ransmissions, and Automation in Design, vol. 5, no. 4, (983), pp [4] Y. Li and Q. Xu, Kinematic analysis of a 3-PRS parallel manipulator, Robotics and Computer-Integrated Manufacturing, vol. 3, no. 4, (7), pp [5] D. Liu, R. Che, Z. Li and X. Luo, Research on the theory and the virtual prototype of 3-DOF parallel-link coordinate-measuring machine, IEEE ransactions on Instrumentation and Measurement, vol. 5, no., (3), pp [6] N. A. Pouliot, C. M. Gosselin and M. A. Nahon, Motion simulation capabilities of three-degree-of-freedom flight simulators, Journal of Aircraft, vol. 35, no., (998), pp [7] A. A. Selvakumar, R. P. Babu and R. Sivaramakrishnan, Simulation and singularity analysis of 3-PRS parallel manipulator. Proceedings of the 9th IEEE International Conference on Mechatronics and Automation, Chengdu China, () August 5-8, pp [8] J. Wahl,. Articulated tool head, US Patent 6,43,8, () August 3. [9]. Yu, D. Li and B. Song, Research on trajectory planning and simulation of industrial robots based on MALAB-Robotics toolbox, Mechanical Engineer, no. 7, (), pp Author Guoqiang Chen, is currently an associate professor at School of Mechanical and Power Engineering of Henan Polytechnic University, China. His research interests include robot technology, electric vehicle control, motor control, pulse width modulation technology and software design. Copyright c 4 SERSC 4

12 International Journal of Hybrid Information echnology 4 Copyright c 4 SERSC

Prototype Development of a 5-DOF Series-Parallel Robot Based on 3-PRS Mechanism

Prototype Development of a 5-DOF Series-Parallel Robot Based on 3-PRS Mechanism , pp.221-232 http//dx.doi.org/10.14257/ijca.2016.9.9.22 Prototype Development of a 5-DOF Series-Parallel Robot Based on 3-PRS Mechanism Guoqiang Chen*, Junwei Zhao, Xuefeng Li and Fuwei Sun School of Mechanical

More information

ÉCOLE POLYTECHNIQUE DE MONTRÉAL

ÉCOLE POLYTECHNIQUE DE MONTRÉAL ÉCOLE POLYTECHNIQUE DE MONTRÉAL MODELIZATION OF A 3-PSP 3-DOF PARALLEL MANIPULATOR USED AS FLIGHT SIMULATOR MOVING SEAT. MASTER IN ENGINEERING PROJET III MEC693 SUBMITTED TO: Luc Baron Ph.D. Mechanical

More information

An Efficient Method for Solving the Direct Kinematics of Parallel Manipulators Following a Trajectory

An Efficient Method for Solving the Direct Kinematics of Parallel Manipulators Following a Trajectory An Efficient Method for Solving the Direct Kinematics of Parallel Manipulators Following a Trajectory Roshdy Foaad Abo-Shanab Kafr Elsheikh University/Department of Mechanical Engineering, Kafr Elsheikh,

More information

Industrial Robots : Manipulators, Kinematics, Dynamics

Industrial Robots : Manipulators, Kinematics, Dynamics Industrial Robots : Manipulators, Kinematics, Dynamics z z y x z y x z y y x x In Industrial terms Robot Manipulators The study of robot manipulators involves dealing with the positions and orientations

More information

INSTITUTE OF AERONAUTICAL ENGINEERING

INSTITUTE OF AERONAUTICAL ENGINEERING Name Code Class Branch Page 1 INSTITUTE OF AERONAUTICAL ENGINEERING : ROBOTICS (Autonomous) Dundigal, Hyderabad - 500 0 MECHANICAL ENGINEERING TUTORIAL QUESTION BANK : A7055 : IV B. Tech I Semester : MECHANICAL

More information

10/25/2018. Robotics and automation. Dr. Ibrahim Al-Naimi. Chapter two. Introduction To Robot Manipulators

10/25/2018. Robotics and automation. Dr. Ibrahim Al-Naimi. Chapter two. Introduction To Robot Manipulators Robotics and automation Dr. Ibrahim Al-Naimi Chapter two Introduction To Robot Manipulators 1 Robotic Industrial Manipulators A robot manipulator is an electronically controlled mechanism, consisting of

More information

Design, Manufacturing and Kinematic Analysis of a Kind of 3-DOF Translational Parallel Manipulator

Design, Manufacturing and Kinematic Analysis of a Kind of 3-DOF Translational Parallel Manipulator 4-27716195 mme.modares.ac.ir 2* 1-1 -2 - mo_taghizadeh@sbu.ac.ir, 174524155 * - - 194 15 : 195 28 : 195 16 : Design, Manufacturing and Kinematic Analysis of a Kind of -DOF Translational Parallel Manipulator

More information

Novel 6-DOF parallel manipulator with large workspace Daniel Glozman and Moshe Shoham

Novel 6-DOF parallel manipulator with large workspace Daniel Glozman and Moshe Shoham Robotica: page 1 of 5. 2009 Cambridge University Press doi:10.1017/s0263574708005286 Novel 6-DOF parallel manipulator with large workspace Daniel Glozman and Moshe Shoham Robotics Laboratory, Department

More information

Orientation Capability, Error Analysis, and Dimensional Optimization of Two Articulated Tool Heads With Parallel Kinematics

Orientation Capability, Error Analysis, and Dimensional Optimization of Two Articulated Tool Heads With Parallel Kinematics Xin-Jun Liu Institute of Manufacturing Engineering, Department of Precision Instruments, Tsinghua University, Beijing, 100084, People s Republic of China e-mail: XinJunLiu@mail.tsinghua.edu.cn Ilian A.

More information

Dynamics Response of Spatial Parallel Coordinate Measuring Machine with Clearances

Dynamics Response of Spatial Parallel Coordinate Measuring Machine with Clearances Sensors & Transducers 2013 by IFSA http://www.sensorsportal.com Dynamics Response of Spatial Parallel Coordinate Measuring Machine with Clearances Yu DENG, Xiulong CHEN, Suyu WANG Department of mechanical

More information

Trajectory Optimization of Composite-pipe Cutting Based on Robot. Harbin , China. Abstract

Trajectory Optimization of Composite-pipe Cutting Based on Robot. Harbin , China. Abstract , pp.35-4 http//dx.doi.org/10.1457/ijca.016.9.7.1 Trajectory Optimization of Composite-pipe Cutting Based on Robot Bo You 1, Kaixin Li 1, Jiazhong Xu 1, Ming Qiao 1, Bowen Zhang and Wenqiang Wang 1 College

More information

KINEMATIC ANALYSIS OF A NOVEL THREE DEGREE-OF-FREEDOM PLANAR PARALLEL MANIPULATOR

KINEMATIC ANALYSIS OF A NOVEL THREE DEGREE-OF-FREEDOM PLANAR PARALLEL MANIPULATOR International Journal of Robotics and Automation, Vol. 24, No. 2, 2009 KINEMATIC ANALYSIS OF A NOVEL THREE DEGREE-OF-FREEDOM PLANAR PARALLEL MANIPULATOR B. Li, J. Zhao, X. Yang, and Y. Hu Abstract In this

More information

SIMULATION ENVIRONMENT PROPOSAL, ANALYSIS AND CONTROL OF A STEWART PLATFORM MANIPULATOR

SIMULATION ENVIRONMENT PROPOSAL, ANALYSIS AND CONTROL OF A STEWART PLATFORM MANIPULATOR SIMULATION ENVIRONMENT PROPOSAL, ANALYSIS AND CONTROL OF A STEWART PLATFORM MANIPULATOR Fabian Andres Lara Molina, Joao Mauricio Rosario, Oscar Fernando Aviles Sanchez UNICAMP (DPM-FEM), Campinas-SP, Brazil,

More information

FREE SINGULARITY PATH PLANNING OF HYBRID PARALLEL ROBOT

FREE SINGULARITY PATH PLANNING OF HYBRID PARALLEL ROBOT Proceedings of the 11 th International Conference on Manufacturing Research (ICMR2013), Cranfield University, UK, 19th 20th September 2013, pp 313-318 FREE SINGULARITY PATH PLANNING OF HYBRID PARALLEL

More information

Constraint and velocity analysis of mechanisms

Constraint and velocity analysis of mechanisms Constraint and velocity analysis of mechanisms Matteo Zoppi Dimiter Zlatanov DIMEC University of Genoa Genoa, Italy Su S ZZ-2 Outline Generalities Constraint and mobility analysis Examples of geometric

More information

[2] J. "Kinematics," in The International Encyclopedia of Robotics, R. Dorf and S. Nof, Editors, John C. Wiley and Sons, New York, 1988.

[2] J. Kinematics, in The International Encyclopedia of Robotics, R. Dorf and S. Nof, Editors, John C. Wiley and Sons, New York, 1988. 92 Chapter 3 Manipulator kinematics The major expense in calculating kinematics is often the calculation of the transcendental functions (sine and cosine). When these functions are available as part of

More information

Robotics kinematics and Dynamics

Robotics kinematics and Dynamics Robotics kinematics and Dynamics C. Sivakumar Assistant Professor Department of Mechanical Engineering BSA Crescent Institute of Science and Technology 1 Robot kinematics KINEMATICS the analytical study

More information

Dynamics Analysis for a 3-PRS Spatial Parallel Manipulator-Wearable Haptic Thimble

Dynamics Analysis for a 3-PRS Spatial Parallel Manipulator-Wearable Haptic Thimble Dynamics Analysis for a 3-PRS Spatial Parallel Manipulator-Wearable Haptic Thimble Masoud Moeini, University of Hamburg, Oct 216 [Wearable Haptic Thimble,A Developing Guide and Tutorial,Francesco Chinello]

More information

A Comparison Study on Motion/Force Transmissibility of Two Typical 3-DOF Parallel Manipulators: The Sprint Z3 and A3 Tool Heads

A Comparison Study on Motion/Force Transmissibility of Two Typical 3-DOF Parallel Manipulators: The Sprint Z3 and A3 Tool Heads International Journal of Advanced Robotic Systems ARTICLE A Comparison Study on Motion/Force Transmissibility of Two Typical 3-DOF Parallel Manipulators: The Sprint Z3 and A3 Tool Heads Regular Paper Xiang

More information

A New Algorithm for Measuring and Optimizing the Manipulability Index

A New Algorithm for Measuring and Optimizing the Manipulability Index A New Algorithm for Measuring and Optimizing the Manipulability Index Mohammed Mohammed, Ayssam Elkady and Tarek Sobh School of Engineering, University of Bridgeport, USA. Mohammem@bridgeport.edu Abstract:

More information

EE Kinematics & Inverse Kinematics

EE Kinematics & Inverse Kinematics Electric Electronic Engineering Bogazici University October 15, 2017 Problem Statement Kinematics: Given c C, find a map f : C W s.t. w = f(c) where w W : Given w W, find a map f 1 : W C s.t. c = f 1

More information

Modelling and index analysis of a Delta-type mechanism

Modelling and index analysis of a Delta-type mechanism CASE STUDY 1 Modelling and index analysis of a Delta-type mechanism K-S Hsu 1, M Karkoub, M-C Tsai and M-G Her 4 1 Department of Automation Engineering, Kao Yuan Institute of Technology, Lu-Chu Hsiang,

More information

Research on time optimal trajectory planning of 7-DOF manipulator based on genetic algorithm

Research on time optimal trajectory planning of 7-DOF manipulator based on genetic algorithm Acta Technica 61, No. 4A/2016, 189 200 c 2017 Institute of Thermomechanics CAS, v.v.i. Research on time optimal trajectory planning of 7-DOF manipulator based on genetic algorithm Jianrong Bu 1, Junyan

More information

Kinematic Synthesis. October 6, 2015 Mark Plecnik

Kinematic Synthesis. October 6, 2015 Mark Plecnik Kinematic Synthesis October 6, 2015 Mark Plecnik Classifying Mechanisms Several dichotomies Serial and Parallel Few DOFS and Many DOFS Planar/Spherical and Spatial Rigid and Compliant Mechanism Trade-offs

More information

A New Algorithm for Measuring and Optimizing the Manipulability Index

A New Algorithm for Measuring and Optimizing the Manipulability Index DOI 10.1007/s10846-009-9388-9 A New Algorithm for Measuring and Optimizing the Manipulability Index Ayssam Yehia Elkady Mohammed Mohammed Tarek Sobh Received: 16 September 2009 / Accepted: 27 October 2009

More information

1. Introduction 1 2. Mathematical Representation of Robots

1. Introduction 1 2. Mathematical Representation of Robots 1. Introduction 1 1.1 Introduction 1 1.2 Brief History 1 1.3 Types of Robots 7 1.4 Technology of Robots 9 1.5 Basic Principles in Robotics 12 1.6 Notation 15 1.7 Symbolic Computation and Numerical Analysis

More information

A Novel Approach for Direct Kinematics Solution of 3-RRR Parallel Manipulator Following a Trajectory

A Novel Approach for Direct Kinematics Solution of 3-RRR Parallel Manipulator Following a Trajectory 16 th. Annual (International) Conference on Mechanical EngineeringISME2008 May 1416, 2008, Shahid Bahonar University of Kerman, Iran A Novel Approach for Direct Kinematics Solution of 3RRR Parallel Manipulator

More information

Inverse Kinematics Software Design and Trajectory Control Programming of SCARA Manipulator robot

Inverse Kinematics Software Design and Trajectory Control Programming of SCARA Manipulator robot International Journal of Engineering Research and Technology. ISSN 0974-3154 Volume 11, Number 11 (2018), pp. 1759-1779 International Research Publication House http://www.irphouse.com Inverse Kinematics

More information

DOUBLE CIRCULAR-TRIANGULAR SIX-DEGREES-OF- FREEDOM PARALLEL ROBOT

DOUBLE CIRCULAR-TRIANGULAR SIX-DEGREES-OF- FREEDOM PARALLEL ROBOT DOUBLE CIRCULAR-TRIANGULAR SIX-DEGREES-OF- FREEDOM PARALLEL ROBOT V. BRODSKY, D. GLOZMAN AND M. SHOHAM Department of Mechanical Engineering Technion-Israel Institute of Technology Haifa, 32000 Israel E-mail:

More information

Jane Li. Assistant Professor Mechanical Engineering Department, Robotic Engineering Program Worcester Polytechnic Institute

Jane Li. Assistant Professor Mechanical Engineering Department, Robotic Engineering Program Worcester Polytechnic Institute Jane Li Assistant Professor Mechanical Engineering Department, Robotic Engineering Program Worcester Polytechnic Institute What are the DH parameters for describing the relative pose of the two frames?

More information

Kinematic Analysis and Design of a New 3-DOF Translational Parallel Manipulator

Kinematic Analysis and Design of a New 3-DOF Translational Parallel Manipulator Yangmin Li e-mail: ymli@umac.mo Qingsong Xu e-mail: ya47401@umac.mo Department of Electromechanical Engineering, Faculty of Science and echnology, University of Macau, Av. Padre omás Pereira S.J., aipa,

More information

Kinematics of pantograph masts

Kinematics of pantograph masts Kinematics of pantograph masts B. P. Nagaraj, R. Pandiyan ISRO Satellite Centre, Bangalore, 560 017, India and Ashitava Ghosal Dept. of Mechanical Engineering, Indian Institute of Science, Bangalore 560

More information

EEE 187: Robotics Summary 2

EEE 187: Robotics Summary 2 1 EEE 187: Robotics Summary 2 09/05/2017 Robotic system components A robotic system has three major components: Actuators: the muscles of the robot Sensors: provide information about the environment and

More information

Basilio Bona ROBOTICA 03CFIOR 1

Basilio Bona ROBOTICA 03CFIOR 1 Kinematic chains 1 Readings & prerequisites Chapter 2 (prerequisites) Reference systems Vectors Matrices Rotations, translations, roto-translations Homogeneous representation of vectors and matrices Chapter

More information

Advances in Engineering Research, volume 123 2nd International Conference on Materials Science, Machinery and Energy Engineering (MSMEE 2017)

Advances in Engineering Research, volume 123 2nd International Conference on Materials Science, Machinery and Energy Engineering (MSMEE 2017) Advances in Engineering Research, volume nd International Conference on Materials Science, Machinery and Energy Engineering MSMEE Kinematics Simulation of DOF Manipulator Guangbing Bao,a, Shizhao Liu,b,

More information

Inverse Kinematics Analysis for Manipulator Robot With Wrist Offset Based On the Closed-Form Algorithm

Inverse Kinematics Analysis for Manipulator Robot With Wrist Offset Based On the Closed-Form Algorithm Inverse Kinematics Analysis for Manipulator Robot With Wrist Offset Based On the Closed-Form Algorithm Mohammed Z. Al-Faiz,MIEEE Computer Engineering Dept. Nahrain University Baghdad, Iraq Mohammed S.Saleh

More information

ROBOTICS 01PEEQW. Basilio Bona DAUIN Politecnico di Torino

ROBOTICS 01PEEQW. Basilio Bona DAUIN Politecnico di Torino ROBOTICS 01PEEQW Basilio Bona DAUIN Politecnico di Torino Kinematic chains Readings & prerequisites From the MSMS course one shall already be familiar with Reference systems and transformations Vectors

More information

Finding Reachable Workspace of a Robotic Manipulator by Edge Detection Algorithm

Finding Reachable Workspace of a Robotic Manipulator by Edge Detection Algorithm International Journal of Advanced Mechatronics and Robotics (IJAMR) Vol. 3, No. 2, July-December 2011; pp. 43-51; International Science Press, ISSN: 0975-6108 Finding Reachable Workspace of a Robotic Manipulator

More information

Singularity Loci of Planar Parallel Manipulators with Revolute Joints

Singularity Loci of Planar Parallel Manipulators with Revolute Joints Singularity Loci of Planar Parallel Manipulators with Revolute Joints ILIAN A. BONEV AND CLÉMENT M. GOSSELIN Département de Génie Mécanique Université Laval Québec, Québec, Canada, G1K 7P4 Tel: (418) 656-3474,

More information

Chapter 1: Introduction

Chapter 1: Introduction Chapter 1: Introduction This dissertation will describe the mathematical modeling and development of an innovative, three degree-of-freedom robotic manipulator. The new device, which has been named the

More information

Operation Trajectory Control of Industrial Robots Based on Motion Simulation

Operation Trajectory Control of Industrial Robots Based on Motion Simulation Operation Trajectory Control of Industrial Robots Based on Motion Simulation Chengyi Xu 1,2, Ying Liu 1,*, Enzhang Jiao 1, Jian Cao 2, Yi Xiao 2 1 College of Mechanical and Electronic Engineering, Nanjing

More information

Robot Inverse Kinematics Asanga Ratnaweera Department of Mechanical Engieering

Robot Inverse Kinematics Asanga Ratnaweera Department of Mechanical Engieering PR 5 Robot Dynamics & Control /8/7 PR 5: Robot Dynamics & Control Robot Inverse Kinematics Asanga Ratnaweera Department of Mechanical Engieering The Inverse Kinematics The determination of all possible

More information

The Collision-free Workspace of the Tripteron Parallel Robot Based on a Geometrical Approach

The Collision-free Workspace of the Tripteron Parallel Robot Based on a Geometrical Approach The Collision-free Workspace of the Tripteron Parallel Robot Based on a Geometrical Approach Z. Anvari 1, P. Ataei 2 and M. Tale Masouleh 3 1,2 Human-Robot Interaction Laboratory, University of Tehran

More information

Kinematics. Kinematics analyzes the geometry of a manipulator, robot or machine motion. The essential concept is a position.

Kinematics. Kinematics analyzes the geometry of a manipulator, robot or machine motion. The essential concept is a position. Kinematics Kinematics analyzes the geometry of a manipulator, robot or machine motion. The essential concept is a position. 1/31 Statics deals with the forces and moments which are aplied on the mechanism

More information

Robotics. SAAST Robotics Robot Arms

Robotics. SAAST Robotics Robot Arms SAAST Robotics 008 Robot Arms Vijay Kumar Professor of Mechanical Engineering and Applied Mechanics and Professor of Computer and Information Science University of Pennsylvania Topics Types of robot arms

More information

A Novel Kinematic Model of Spatial Four-bar Linkage RSPS for Testing Accuracy of Actual R-Pairs with Ball-bar

A Novel Kinematic Model of Spatial Four-bar Linkage RSPS for Testing Accuracy of Actual R-Pairs with Ball-bar A Novel Kinematic Model of Spatial Four-bar Linkage RSPS for Testing Accuracy of Actual R-Pairs with Ball-bar Zhi Wang 1, Delun Wang 1 *, Xiaopeng Li 1, Huimin Dong 1 and Shudong Yu 1, 2 1 School of Mechanical

More information

Chapter 2 Kinematics of Mechanisms

Chapter 2 Kinematics of Mechanisms Chapter Kinematics of Mechanisms.1 Preamble Robot kinematics is the study of the motion (kinematics) of robotic mechanisms. In a kinematic analysis, the position, velocity, and acceleration of all the

More information

Mechanism Design for 3-, 4-, 5- and 6-DOF PMWPSs

Mechanism Design for 3-, 4-, 5- and 6-DOF PMWPSs Proceedings of the 6th WSEAS International Conference on Robotics Control and Manufacturing Technolog Hanghou China April 6-8 26 (pp93-98) Mechanism Design for 3-4- 5- and 6-DOF PMWPSs JIANJUN ZHANG XIAOHUI

More information

SCREW-BASED RELATIVE JACOBIAN FOR MANIPULATORS COOPERATING IN A TASK

SCREW-BASED RELATIVE JACOBIAN FOR MANIPULATORS COOPERATING IN A TASK ABCM Symposium Series in Mechatronics - Vol. 3 - pp.276-285 Copyright c 2008 by ABCM SCREW-BASED RELATIVE JACOBIAN FOR MANIPULATORS COOPERATING IN A TASK Luiz Ribeiro, ribeiro@ime.eb.br Raul Guenther,

More information

Extension of Usable Workspace of Rotational Axes in Robot Planning

Extension of Usable Workspace of Rotational Axes in Robot Planning Extension of Usable Workspace of Rotational Axes in Robot Planning Zhen Huang' andy. Lawrence Yao Department of Mechanical Engineering Columbia University New York, NY 127 ABSTRACT Singularity of a robot

More information

Rigid Dynamics Solution Methodology for 3-PSU Parallel Kinematic Manipulators

Rigid Dynamics Solution Methodology for 3-PSU Parallel Kinematic Manipulators Rigid Dynamics Solution Methodology for 3-PSU Parallel Kinematic Manipulators Arya B. Changela 1, Dr. Ramdevsinh Jhala 2, Chirag P. Kalariya 3 Keyur P. Hirpara 4 Assistant Professor, Department of Mechanical

More information

Serial Manipulator Statics. Robotics. Serial Manipulator Statics. Vladimír Smutný

Serial Manipulator Statics. Robotics. Serial Manipulator Statics. Vladimír Smutný Serial Manipulator Statics Robotics Serial Manipulator Statics Vladimír Smutný Center for Machine Perception Czech Institute for Informatics, Robotics, and Cybernetics (CIIRC) Czech Technical University

More information

A Family of New Parallel Architectures with Four Degrees of Freedom

A Family of New Parallel Architectures with Four Degrees of Freedom A Family of New arallel Architectures with Four Degrees of Freedom DIMITER ZLATANOV AND CLÉMENT M. GOSSELIN Département de Génie Mécanique Université Laval Québec, Québec, Canada, G1K 74 Tel: (418) 656-3474,

More information

Linear algebra deals with matrixes: two-dimensional arrays of values. Here s a matrix: [ x + 5y + 7z 9x + 3y + 11z

Linear algebra deals with matrixes: two-dimensional arrays of values. Here s a matrix: [ x + 5y + 7z 9x + 3y + 11z Basic Linear Algebra Linear algebra deals with matrixes: two-dimensional arrays of values. Here s a matrix: [ 1 5 ] 7 9 3 11 Often matrices are used to describe in a simpler way a series of linear equations.

More information

Robot mechanics and kinematics

Robot mechanics and kinematics University of Pisa Master of Science in Computer Science Course of Robotics (ROB) A.Y. 2016/17 cecilia.laschi@santannapisa.it http://didawiki.cli.di.unipi.it/doku.php/magistraleinformatica/rob/start Robot

More information

Parallel Robots. Mechanics and Control H AMID D. TAG HI RAD. CRC Press. Taylor & Francis Group. Taylor & Francis Croup, Boca Raton London NewYoric

Parallel Robots. Mechanics and Control H AMID D. TAG HI RAD. CRC Press. Taylor & Francis Group. Taylor & Francis Croup, Boca Raton London NewYoric Parallel Robots Mechanics and Control H AMID D TAG HI RAD CRC Press Taylor & Francis Group Boca Raton London NewYoric CRC Press Is an Imprint of the Taylor & Francis Croup, an informs business Contents

More information

KINEMATIC AND DYNAMIC SIMULATION OF A 3DOF PARALLEL ROBOT

KINEMATIC AND DYNAMIC SIMULATION OF A 3DOF PARALLEL ROBOT Bulletin of the Transilvania University of Braşov Vol. 8 (57) No. 2-2015 Series I: Engineering Sciences KINEMATIC AND DYNAMIC SIMULATION OF A 3DOF PARALLEL ROBOT Nadia Ramona CREŢESCU 1 Abstract: This

More information

KINEMATIC ANALYSIS OF 3 D.O.F OF SERIAL ROBOT FOR INDUSTRIAL APPLICATIONS

KINEMATIC ANALYSIS OF 3 D.O.F OF SERIAL ROBOT FOR INDUSTRIAL APPLICATIONS KINEMATIC ANALYSIS OF 3 D.O.F OF SERIAL ROBOT FOR INDUSTRIAL APPLICATIONS Annamareddy Srikanth 1 M.Sravanth 2 V.Sreechand 3 K.Kishore Kumar 4 Iv/Iv B.Tech Students, Mechanical Department 123, Asst. Prof.

More information

θ x Week Date Lecture (M: 2:05p-3:50, 50-N202) 1 23-Jul Introduction + Representing Position & Orientation & State 2 30-Jul

θ x Week Date Lecture (M: 2:05p-3:50, 50-N202) 1 23-Jul Introduction + Representing Position & Orientation & State 2 30-Jul θ x 2018 School of Information Technology and Electrical Engineering at the University of Queensland Lecture Schedule Week Date Lecture (M: 2:05p-3:50, 50-N202) 1 23-Jul Introduction + Representing Position

More information

MOTION TRAJECTORY PLANNING AND SIMULATION OF 6- DOF MANIPULATOR ARM ROBOT

MOTION TRAJECTORY PLANNING AND SIMULATION OF 6- DOF MANIPULATOR ARM ROBOT MOTION TRAJECTORY PLANNING AND SIMULATION OF 6- DOF MANIPULATOR ARM ROBOT Hongjun ZHU ABSTRACT:In order to better study the trajectory of robot motion, a motion trajectory planning and simulation based

More information

An Improved Dynamic Modeling of a 3-RPS Parallel Manipulator using the concept of DeNOC Matrices

An Improved Dynamic Modeling of a 3-RPS Parallel Manipulator using the concept of DeNOC Matrices An Improved Dynamic Modeling of a 3-RPS Parallel Manipulator using the concept of DeNOC Matrices A. Rahmani Hanzaki, E. Yoosefi Abstract A recursive dynamic modeling of a three-dof parallel robot, namely,

More information

Using Algebraic Geometry to Study the Motions of a Robotic Arm

Using Algebraic Geometry to Study the Motions of a Robotic Arm Using Algebraic Geometry to Study the Motions of a Robotic Arm Addison T. Grant January 28, 206 Abstract In this study we summarize selected sections of David Cox, John Little, and Donal O Shea s Ideals,

More information

Design of a Three-Axis Rotary Platform

Design of a Three-Axis Rotary Platform Design of a Three-Axis Rotary Platform William Mendez, Yuniesky Rodriguez, Lee Brady, Sabri Tosunoglu Mechanics and Materials Engineering, Florida International University 10555 W Flagler Street, Miami,

More information

Optimum Design of Kinematically Redundant Planar Parallel Manipulator Following a Trajectory

Optimum Design of Kinematically Redundant Planar Parallel Manipulator Following a Trajectory International Journal of Materials, Mechanics and Manufacturing, Vol., No., May 1 Optimum Design of Kinematically Redundant Planar Parallel Manipulator Following a rajectory K. V. Varalakshmi and J. Srinivas

More information

A Review Paper on Analysis and Simulation of Kinematics of 3R Robot with the Help of RoboAnalyzer

A Review Paper on Analysis and Simulation of Kinematics of 3R Robot with the Help of RoboAnalyzer A Review Paper on Analysis and Simulation of Kinematics of 3R Robot with the Help of RoboAnalyzer Ambuja Singh Student Saakshi Singh Student, Ratna Priya Kanchan Student, Abstract -Robot kinematics the

More information

Planar Robot Kinematics

Planar Robot Kinematics V. Kumar lanar Robot Kinematics The mathematical modeling of spatial linkages is quite involved. t is useful to start with planar robots because the kinematics of planar mechanisms is generally much simpler

More information

Kinematics Fundamentals CREATING OF KINEMATIC CHAINS

Kinematics Fundamentals CREATING OF KINEMATIC CHAINS Kinematics Fundamentals CREATING OF KINEMATIC CHAINS Mechanism Definitions 1. a system or structure of moving parts that performs some function 2. is each system reciprocally joined moveable bodies the

More information

Kinematic Model Analysis of an 8-DOF Photographic Robot

Kinematic Model Analysis of an 8-DOF Photographic Robot Kinematic Model Analysis of an 8-DOF Photographic Robot Xiaowei Xie, Xingang Miao, Su Wang and Feng Zhang Abstract The photographic robot studied in this chapter is an 8-DOF PRRPR-S type. In order to obtain

More information

10/11/07 1. Motion Control (wheeled robots) Representing Robot Position ( ) ( ) [ ] T

10/11/07 1. Motion Control (wheeled robots) Representing Robot Position ( ) ( ) [ ] T 3 3 Motion Control (wheeled robots) Introduction: Mobile Robot Kinematics Requirements for Motion Control Kinematic / dynamic model of the robot Model of the interaction between the wheel and the ground

More information

Inverse kinematics Analysis and Solution of Six Degree of Freedom Industrial Robot Based on Projective Method of Descriptive Geometry

Inverse kinematics Analysis and Solution of Six Degree of Freedom Industrial Robot Based on Projective Method of Descriptive Geometry IOSR Journal of Electronics and Communication Engineering (IOSR-JECE) e-issn: 2278-2834,p- ISSN: 2278-8735.Volume 12, Issue 4, Ver. III (Jul.-Aug. 2017), PP 31-42 www.iosrjournals.org Inverse kinematics

More information

UNIVERSITY OF OSLO. Faculty of Mathematics and Natural Sciences

UNIVERSITY OF OSLO. Faculty of Mathematics and Natural Sciences Page 1 UNIVERSITY OF OSLO Faculty of Mathematics and Natural Sciences Exam in INF3480 Introduction to Robotics Day of exam: May 31 st 2010 Exam hours: 3 hours This examination paper consists of 5 page(s).

More information

METR 4202: Advanced Control & Robotics

METR 4202: Advanced Control & Robotics Position & Orientation & State t home with Homogenous Transformations METR 4202: dvanced Control & Robotics Drs Surya Singh, Paul Pounds, and Hanna Kurniawati Lecture # 2 July 30, 2012 metr4202@itee.uq.edu.au

More information

Robot. A thesis presented to. the faculty of. In partial fulfillment. of the requirements for the degree. Master of Science. Zachary J.

Robot. A thesis presented to. the faculty of. In partial fulfillment. of the requirements for the degree. Master of Science. Zachary J. Uncertainty Analysis throughout the Workspace of a Macro/Micro Cable Suspended Robot A thesis presented to the faculty of the Russ College of Engineering and Technology of Ohio University In partial fulfillment

More information

PPGEE Robot Dynamics I

PPGEE Robot Dynamics I PPGEE Electrical Engineering Graduate Program UFMG April 2014 1 Introduction to Robotics 2 3 4 5 What is a Robot? According to RIA Robot Institute of America A Robot is a reprogrammable multifunctional

More information

Open Access The Kinematics Analysis and Configuration Optimize of Quadruped Robot. Jinrong Zhang *, Chenxi Wang and Jianhua Zhang

Open Access The Kinematics Analysis and Configuration Optimize of Quadruped Robot. Jinrong Zhang *, Chenxi Wang and Jianhua Zhang Send Orders for Reprints to reprints@benthamscience.ae The Open Automation and Control Systems Journal, 014, 6, 1685-1690 1685 Open Access The Kinematics Analysis and Configuration Optimize of Quadruped

More information

Accurate Trajectory Control for Five-Axis Tool-Path Planning

Accurate Trajectory Control for Five-Axis Tool-Path Planning Accurate Trajectory Control for Five-Axis Tool-Path Planning Rong-Shine Lin* and Cheng-Bing Ye Abstract Computer-Aided Manufacturing technology has been widely used for three-axis CNC machining in industry

More information

MCE/EEC 647/747: Robot Dynamics and Control. Lecture 1: Introduction

MCE/EEC 647/747: Robot Dynamics and Control. Lecture 1: Introduction MCE/EEC 647/747: Robot Dynamics and Control Lecture 1: Introduction Reading: SHV Chapter 1 Robotics and Automation Handbook, Chapter 1 Assigned readings from several articles. Cleveland State University

More information

Solving IK problems for open chains using optimization methods

Solving IK problems for open chains using optimization methods Proceedings of the International Multiconference on Computer Science and Information Technology pp. 933 937 ISBN 978-83-60810-14-9 ISSN 1896-7094 Solving IK problems for open chains using optimization

More information

Written exams of Robotics 2

Written exams of Robotics 2 Written exams of Robotics 2 http://www.diag.uniroma1.it/~deluca/rob2_en.html All materials are in English, unless indicated (oldies are in Year Date (mm.dd) Number of exercises Topics 2018 07.11 4 Inertia

More information

Xi'an Technological University.

Xi'an Technological University. 6th International Conference on Mechatronics, Computer and Education Informationization (MCEI 016) Mechanical System Design and Analysis of Three Dimensional Scanning Probe Based on Flexible Parallel Mechanism

More information

Geometric Approach For Inverse Kinematics Solution: 3-PSU Parallel Kinematic Manipulator

Geometric Approach For Inverse Kinematics Solution: 3-PSU Parallel Kinematic Manipulator Geometric Approach For Inverse Kinematics Solution: 3-PSU Parallel Kinematic Manipulator Mr. Arya B Changela P.G. Student, School of Engineering RK University, Rajkot. Prof. Keyur P Hirpara Assistant Professor,

More information

Chapter 4. Mechanism Design and Analysis

Chapter 4. Mechanism Design and Analysis Chapter 4. Mechanism Design and Analysis All mechanical devices containing moving parts are composed of some type of mechanism. A mechanism is a group of links interacting with each other through joints

More information

Force-Moment Capabilities of Redundantly-Actuated Planar-Parallel Architectures

Force-Moment Capabilities of Redundantly-Actuated Planar-Parallel Architectures Force-Moment Capabilities of Redundantly-Actuated Planar-Parallel Architectures S. B. Nokleby F. Firmani A. Zibil R. P. Podhorodeski UOIT University of Victoria University of Victoria University of Victoria

More information

Robotics I. March 27, 2018

Robotics I. March 27, 2018 Robotics I March 27, 28 Exercise Consider the 5-dof spatial robot in Fig., having the third and fifth joints of the prismatic type while the others are revolute. z O x Figure : A 5-dof robot, with a RRPRP

More information

Optimal Design of a 6-DOF 4-4 Parallel Manipulator with Uncoupled Singularities

Optimal Design of a 6-DOF 4-4 Parallel Manipulator with Uncoupled Singularities Optimal Design of a 6-DOF 4-4 Parallel Manipulator with Uncoupled Singularities Júlia Borràs (1), Erika Ottaviano (2), Marco Ceccarelli (2) and Federico Thomas (1) (1) Institut de Robòtica i Informàtica

More information

Geometric Modeling of Parallel Robot and Simulation of 3-RRR Manipulator in Virtual Environment

Geometric Modeling of Parallel Robot and Simulation of 3-RRR Manipulator in Virtual Environment Geometric Modeling of Parallel Robot and Simulation of 3-RRR Manipulator in Virtual Environment Kamel BOUZGOU, Reda HANIFI EL HACHEMI AMAR, Zoubir AHMED-FOITIH Laboratory of Power Systems, Solar Energy

More information

Forward kinematics and Denavit Hartenburg convention

Forward kinematics and Denavit Hartenburg convention Forward kinematics and Denavit Hartenburg convention Prof. Enver Tatlicioglu Department of Electrical & Electronics Engineering Izmir Institute of Technology Chapter 5 Dr. Tatlicioglu (EEE@IYTE) EE463

More information

Theory of Robotics and Mechatronics

Theory of Robotics and Mechatronics Theory of Robotics and Mechatronics Final Exam 19.12.2016 Question: 1 2 3 Total Points: 18 32 10 60 Score: Name: Legi-Nr: Department: Semester: Duration: 120 min 1 A4-sheet (double sided) of notes allowed

More information

CALCULATING TRANSFORMATIONS OF KINEMATIC CHAINS USING HOMOGENEOUS COORDINATES

CALCULATING TRANSFORMATIONS OF KINEMATIC CHAINS USING HOMOGENEOUS COORDINATES CALCULATING TRANSFORMATIONS OF KINEMATIC CHAINS USING HOMOGENEOUS COORDINATES YINGYING REN Abstract. In this paper, the applications of homogeneous coordinates are discussed to obtain an efficient model

More information

Singularities of a Manipulator with Offset Wrist

Singularities of a Manipulator with Offset Wrist Singularities of a Manipulator with Offset Wrist Robert L. Williams II Department of Mechanical Engineering Ohio University Athens, Ohio Journal of Mechanical Design Vol. 11, No., pp. 315-319 June, 1999

More information

Workspace and joint space analysis of the 3-RPS parallel robot

Workspace and joint space analysis of the 3-RPS parallel robot Workspace and joint space analysis of the 3-RPS parallel robot Damien Chablat, Ranjan Jha, Fabrice Rouillier, Guillaume Moroz To cite this version: Damien Chablat, Ranjan Jha, Fabrice Rouillier, Guillaume

More information

Research on Adaptive Control System of Robot Arm with Six Degrees of Freedom

Research on Adaptive Control System of Robot Arm with Six Degrees of Freedom 6th International Conference on Sensor Network and Computer Engineering (ICSNCE 2016) Research on Adaptive Control System of Robot Arm with Six Degrees of Freedom Changgeng Yu 1, a and Suyun Li 1, b,*

More information

Inverse Kinematics. Given a desired position (p) & orientation (R) of the end-effector

Inverse Kinematics. Given a desired position (p) & orientation (R) of the end-effector Inverse Kinematics Given a desired position (p) & orientation (R) of the end-effector q ( q, q, q ) 1 2 n Find the joint variables which can bring the robot the desired configuration z y x 1 The Inverse

More information

WORKSPACE AGILITY FOR ROBOTIC ARM Karna Patel

WORKSPACE AGILITY FOR ROBOTIC ARM Karna Patel ISSN 30-9135 1 International Journal of Advance Research, IJOAR.org Volume 4, Issue 1, January 016, Online: ISSN 30-9135 WORKSPACE AGILITY FOR ROBOTIC ARM Karna Patel Karna Patel is currently pursuing

More information

Articulated Robots! Robert Stengel! Robotics and Intelligent Systems! MAE 345, Princeton University, 2017

Articulated Robots! Robert Stengel! Robotics and Intelligent Systems! MAE 345, Princeton University, 2017 Articulated Robots! Robert Stengel! Robotics and Intelligent Systems! MAE 345, Princeton University, 2017 Robot configurations Joints and links Joint-link-joint transformations! Denavit-Hartenberg representation

More information

Kinematics of the Stewart Platform (Reality Check 1: page 67)

Kinematics of the Stewart Platform (Reality Check 1: page 67) MATH 5: Computer Project # - Due on September 7, Kinematics of the Stewart Platform (Reality Check : page 7) A Stewart platform consists of six variable length struts, or prismatic joints, supporting a

More information

Simulation Model for Coupler Curve Generation using Five Bar Planar Mechanism With Rotation Constraint

Simulation Model for Coupler Curve Generation using Five Bar Planar Mechanism With Rotation Constraint Simulation Model for Coupler Curve Generation using Five Bar Planar Mechanism With Rotation Constraint A. K. Abhyankar, S.Y.Gajjal Department of Mechanical Engineering, NBN Sinhgad School of Engineering,

More information

Workspace Optimization of 3-Legged UPU and UPS Parallel Platforms With Joint Constraints

Workspace Optimization of 3-Legged UPU and UPS Parallel Platforms With Joint Constraints Mircea Badescu Caltech Postdoctoral Scholar, Mem. ASME e-mail: mircea.badescu@jpl.nasa.gov Constantinos Mavroidis Associate Professor, Mem. ASME e-mail: mavro@coe.neu.edu Robotics and Mechatronics Laboratory,

More information

Kinematics, Kinematics Chains CS 685

Kinematics, Kinematics Chains CS 685 Kinematics, Kinematics Chains CS 685 Previously Representation of rigid body motion Two different interpretations - as transformations between different coord. frames - as operators acting on a rigid body

More information

Kinematic Analysis and Optimum Design of 8-8 Redundant Spatial In-Parallel Maniputator

Kinematic Analysis and Optimum Design of 8-8 Redundant Spatial In-Parallel Maniputator Kinematic Analysis and Optimum Design of 8-8 Redundant Spatial In-Parallel Maniputator P.Chinna Srinivas M.Tech(CAD/CAM) Department Of Mechanical Engineering Jb Institute Of Engineering& Technology,Moinabad(Mdl)

More information