0% found this document useful (0 votes)
230 views

Ur 5

manipulator
Copyright
© © All Rights Reserved
We take content rights seriously. If you suspect this is your content, claim it here.
Available Formats
Download as PDF, TXT or read online on Scribd
0% found this document useful (0 votes)
230 views

Ur 5

manipulator
Copyright
© © All Rights Reserved
We take content rights seriously. If you suspect this is your content, claim it here.
Available Formats
Download as PDF, TXT or read online on Scribd
You are on page 1/ 6

2016 IEEE International Conference on Systems, Man, and Cybernetics • SMC 2016 | October 9-12, 2016 • Budapest, Hungary

Kinematic and Dynamic Modelling of UR5 Manipulator


Parham M. Kebria1 , Saba Al-wais, Hamid Abdi, and Saeid Nahavandi

Abstract— UR robotic arms are from a series of lightweight, is no Simmechanics model for the UR5. This shortcoming
fast, easy to program, flexible, and safe robotic arms with motivated us to develop a complete set of MATLAB based
6 degrees of freedom. The fairly open control structure and models for this robot.
low level programming access with high control bandwidth
have made them of interest for many researchers. This paper Within the literature, lots of modelling studies are available
presents a complete set of mathematical kinematic and dynamic, for different robotic manipulators. More specifically, there is
Matlab, and Simmechanics models for the UR5 robot. The accu- a great amount of literature for acclaimed manipulators such
racy of the developed mathematical models are demonstrated as PUMA 560 [24]. Furthermore, lots of studies have been
through kinematic and dynamic analysis. The Simmechanics done under the title of modelling of 6 DoF manipulators.
model is developed based on these models to provide high
quality visualisation of this robot for simulation of it in Matlab The main reason of existence of this much of literature
environment. The models are developed for public access and around this problem are: these models are essential for many
readily usable in Matlab environment. A position control system research activities and the parameters of the models are
has been developed to demonstrate the use of the models and different for different robots, even with similar structure. Fur-
for cross validation purpose. thermore, development of these models are also a challenging
I. I NTRODUCTION problem because such development is time consuming and
involves tedious and lengthy mathematical formulation.
Serial manipulators are used in many robotic systems. In the present paper, a thorough mathematical model for
The serial robots are widely used in manufacturing, handling kinematics and dynamics of the UR5 robot is presented. The
material, and tele-operation. There is an increasing number of kinematic model includes full mathematical development for
these robots worldwide with some big names in that domain the forward and inverse kinematic equations of the robot.
such as ABB and Kuka. While the science of these robots The dynamic model gives the equation of motion of the
are well understood, the main challenge associated with these robot and access to the parameters of that equation including
robots are improving the functionality, flexibility, reliability, the mass inertial matrix, centrifugal and Coriolis matrix
safety and bandwidth of them. In the recent years, Universal and gravity force vector. These models are implemented in
robots have developed a series of robotic manipulators that Matlab environment with the codes of them for public access.
is now widely used by many universities and industries. This Furthermore, a very accurate SimMechanics model of this
robot is claimed to be fast, easy to program, flexible, safe and robot is developed again in Matlab Simulink environment.
offers low level programming access of the robot controller These models could be readily used by any researcher using
with high cycle time [1]. Among the UR products the family the UR5 robot. The main contribution of this paper is the
of UR3, UR5 and UR10 have received a great attention development of a complete MATLAB based models for the
within the robotics community and industries specifically by UR5 robot with evaluating the accuracy of these models.
the robotic research community. According to the authors research, this is the most accurate
For development of a robotic system based on the UR kinematic and dynamic model of the UR5 to date.
arms, researchers require to have access to precise mathemat- The paper is outlined as follows: Section II introduces
ical and simulation models of the UR robots. Such models the UR5 robot and describes the mathematical modelling
are essential for motion planning [2]–[4], position and force for kinematics and dynamics of this robot. In Section III
control system design [5]–[8], and customising the robot for mathematical model used for implementation of the models
novel applications. Currently the UR5 robot comes with a in MATLAB for public access. Following that, development
URSim software that is used for simulation of this robot. of the SimMechanics model is detailed and shown in Section
However, the URSim is fairly limited in terms of access to IV. Then in Section V, a cross validation is performed for
details of the mathematical model of the robot [1]. According evaluating the accuracy of the models. Finally, the conclud-
to the authors’ research, currently there is no complete ing remarks are stated in Section VI.
mathematical and Simmechanics models for the UR5 robot
that could be publicly and readily accessible for Matlab II. M ATHEMATICAL M ODELLING
or any other environment. Researchers developed different A. UR5 robot
models for UR5 robot from scratch. [9]–[23], however these
UR5, Fig. 1, is a well-known 6-degree-of-freedom (DoF)
models are either incomplete (eg. only kinematic model)
robotic manipulator manufactured by Universal Robots Com-
or they are not in Matlab environment. Furthermore there
pany [1]. The most renowned feature of this robot is its
1 Authors are with the Institute for Intelligent Systems Research and agility due to its light weight, speed, easy to program,
Innovation, Deakin University, Australia. [email protected] flexibility, and safety. One of the main characteristic of

978-1-5090-1897-0/16/$31.00 ©2016 IEEE SMC_2016 004229


2016 IEEE International Conference on Systems, Man, and Cybernetics • SMC 2016 | October 9-12, 2016 • Budapest, Hungary

TABLE I
DH PARAMETERS OF UR5

i ai αi di θi
0 0 0 - -
π
1 0 2
0.08916 θ1
2 0.425 0 0 θ2
3 0.39225 0 0 θ3
π
4 0 2
0.10915 θ4
5 0 − π2 0.09456 θ5
6 - - 0.0823 θ6

C. Forward Kinematics
Using the definition of the transformation matrix of a
robotic arm from [27], [28], the transformation matrix from
the base to the end effector is in the form of :
 
nx ox ax px
0
 ny oy ay py 
Tn = 
 nz oz az pz 
 (1)
Fig. 2. Schematic and frames assignment of UR5 [25]. 0 0 0 1

Then the forward kinematics of the robot position would


the UR5 is that the last three joints of it do not act as a easily obtained from the fourth column of the 0 Tn in 1 as:
coincidental wrist. Therefore all its six joints contribute to
the transformational and rotational movements of its end- px =d5 c1 s234 + d4 s1 − d6 c1 c234 + a2 c1 c2 + d6 c5 s1
effector. This characteristic makes the kinematics analysis + a3 c1 c2 c3 − a3 c1 s2 s3
more complex in comparison with other manipulators with py =d5 s1 s234 − d4 c1 − d6 s1 c234 − d6 c1 c5 + a2 c2 s1 (2)
coincidental wrist.
+ a3 c2 c3 s1 − a3 s1 s2 s3
pz =d1 − d6 s234 s5 + a3 s23 + a2 s2 − d5 c234

where s234 represents the sin(θ2 + θ3 + θ4 ) and c234 for the


cos(.) of the same.

D. Inverse kinematics
For inverse kinematics, we will find the set of joint
configurations Q = qi where qi = [θ1i , . . . , θ6i ]T ∈ [0, 2π)6
such that satisfies 1 which describes the desired position
and orientation of the the last link. Derivation of the inverse
kinematic in this section is adopted from [29].
Fig. 1. The real UR5 manipulator.
First, finding θ1 using the position of the 5th joint.
Analyzing the transformation from frame 1 to frame 5 using
As it was mentioned earlier, currently there is no complete equation 1, which results:
set of Matlab models for this robot. Therefore we tried to fill
this gap. To achieve this goal, we searched and used the most −s1 (px − d6 zx ) + c1 (py − d6 zy ) = −d4
valid parameters and measurements of UR5 parameters that
are used for the development of the models in this paper [25] that is known as a phase-shift equation whose solution
[26]. Obviously, the more precise model, the more valuable considering Fig. 3 can be found as:
and accurate results could be obtained from those models. 0
p5y
tan α1 = 0
B. Characterization of kinematic parameters of UR5 p5x
d4 d4
In the Fig. 2 the schematic of the robotic arm and the tan α2 = = q
R 0 p2 + 0 p2
allocation of each joint’s frame are illustrated. It is mentioned 5x 5y
that the DH parameters and rotation matrices that are used
for kinematic model are based on these frames. The DH Hence
parameters of the UR5 [27], [28] for the specified joint π d4 π
frames in Figure2, are presented in the Table I: θ1 = α1 +α2 + = atan2(0 p5y , 0 p5x )±cos−1 + (3)
2 R 2

SMC_2016 004230
2016 IEEE International Conference on Systems, Man, and Cybernetics • SMC 2016 | October 9-12, 2016 • Budapest, Hungary

Fig. 5. Geometry for finding θ6 .

When s5 = 0, we know c5 = ±1, which indicates that


Fig. 3. Geometry of finding θ1 .
the joints 2, 3, 4, and 6 are all parallel and the solution is
undetermined. When this occurs, a desired θ6 can be supplied
There exist two solutions for θ1 , where the shoulder is to fully determine the system.
”left” or ”right”. Using the function atan2 is essential for The other 3 joints can be derived easily, considering that
insuring correct signs and behavior when 0 p5x = 0. In Fig. 3, they act as a 3-RRR planar arm. Once the previous 3 joints
it is easy to see
q that physically, no configuration is possible found, the location of the base and end-effector of this 3-
which makes 0 p25x + 0 p25y ≤ |d4 | < 0. Thus, both α1 and RRR arm is available, then these 3 joints can be solved.
α2 always exist if an inverse solution exists. There is two possible configurations, ”elbow up” or ”elbow
Given a particular θ1 , we can solve for θ5 . Using the down”. No solutions exist when the distance to the 4th joint
transformation from frame 1 to frame 6, we can form the exceeds the sum |a2 + a3 | or is less than the difference |a2 −
below equality: a3 |. If a2 = a3 , a singularity exists when θ3 = π, making
  θ2 arbitrary.
  px
−s1 c1 0  py  = −d4 − c5 d5 E. Dynamics
pz
The manipulators’ dynamic equations have the general
which results to: form of:
px s1 − py c1 − d4 M (q)q̈ + C(q, q̇)q̇ + g(q) = u (6)
θ5 = ± cos−1 (4)
d6 where M (q) is the symmetric positive definite mass inertia
Again, there are 2 solutions for θ5 , which correspond to matrix of the system, C(q, q̇) is the matrix of Coriolis and
configurations where the wrist is ”in/down” or ”out/up”. centrifugal terms, g(q) is the vector of gravity terms and u
is the input vector. The inverse dynamic has the form:
 
q̈ = M −1 (q) u − C(q, q̇)q̇ − g(q) (7)

The matrix M (q) would be simply calculated as [27], [28]:


X n  
M (q) = mi JvTi Jvi + JωTi Ri Ii RiT Jωi (8)
i=1

where Jvi and Jωi are the linear and angular part of the
Jacobian matrix Ji , respectively.
For deriving the matrix C(q, q̇) it would be useful to
know the passivity property of robotic manipulators which
Fig. 4. Geometry of finding θ5 . is the result of the skew-symmetry property of the matrix
Ṁ (q) − 2C(q, q̇). For reaching this property the elements
To solve for the 6th joint, we look at the 6 y1 coordinate of the matrix cij must be derived from the elements of the
axis:     inertia matrix mij via the following formula [27], [28]:
−xx s1 + xy c1 −c6 c5 n
 −yx s1 + yy c1  =  s6 s5 
X 1  ∂mij ∂mik ∂mkj 
cij = + − q̇k (9)
−zx s1 + zy c1 −c5 2 ∂qk ∂qj ∂qi
k=1

As Fig. 5 shows, this equality forms a spherical coordinate Finally, the elements of the gravity vector gi (q) [27], [28]:
expression for the vector 6 y1 where θ6 is the azimuthal angle
and θ5 is the polar angle. The x and y coordinates of this ∂P
gi (q) = (10)
vector form a system which can be easily solved as: ∂qi
yy c1 − yx s1 xx c1 − xy s1 Having M (q) , C(q, q̇) and gi (q) completes the dynamical
θ6 = atan2( , ) (5) model development.
s5 s5

SMC_2016 004231
2016 IEEE International Conference on Systems, Man, and Cybernetics • SMC 2016 | October 9-12, 2016 • Budapest, Hungary

III. MATLAB M ODEL D EVELOPMENT


The mathematical models of the kinematics and dynamics
in the previous section have been used to develop the Matlab
model for the robot here. The developed code follows the
strategy of the previous section that is briefly itemized in
below:
1) First, all the DH and inertia parameters of UR5, and
necessary symbols would be valued or defined.
2) Secondly, rotation matrices and position vectors of all
the joints’ frame origins (forward kinematics).
3) Subsequently, position of all CoMs are calculated from
base to end-effector.
4) Then, linear and angular parts of Jacobian matrices are
derived via the formulations stated in [27], [28].
5) After that, the inertia (M ) matrix of the robot is
derived using the method 8.
6) The centrifugal and Coriolis matrix (C) is obtained at
Fig. 6. UR5 Simmechanics blocks in Matlab Simulink
this stage, having the inertia matrix and applying 9.
7) Finally, potential energy and gravity terms of the robot
are calculated, respectively using 10.
This script file of the models is available through the
link1 . It is worthy to mention that all the required values
and parameters of the robot which adopted from the most
accurate available sources such as [25], [26], are saved
and accessible in this MATLAB m.file. Also, the results of
this procedure contain the robot’s joints angle and angular
velocity as symbolic variables. The outcomes are used to
develop a Simulink/SimMechanics model for simulation.
They are used in the controller structure, as will be detailed
later in this paper. Fig. 7. The robot’s Base block details
IV. S IMMECHANICS M ODEL D EVELOPMENT
For developing Simmechanics model of a robotic system
of Simmechanics model of the UR5. Details of the block of
knowing the physical parameters and structural properties
the Robot part are explained in below.
of the robot is essential. At the first step, coordination,
orientation and dimension of each parts of the robot are A. Base block
required. DH parameters are considered to provide these
For any Simmechanics model, it is needed to use three
geometrical specifications of the robot. The second step is to
basic blocks that are Solver, World frame and Mechanism
assign mass, centre of mass and inertia tensor, for each part
configuration blocks. These blocks define the system’s envi-
of the robot. It is noted that in the Simmechanics models,
ronment (world) and its properties, such as gravity constant
the COMs should be expressed in a frame located at the
and direction. The base of the robot should be defined
centre of geometry (CoG) of the body. This is different with
immediately after the block World frame. These blocks are
the CoM obtained by DH parameters, because the CoM
depicted in Fig. 7. The block with the name of Solid in this
based on the DH parameters are commonly expressed in
figure is a representative of the pedestal or base of the robot.
the joint frames. Therefore, for the Simemchanics model
For the Base block, there is an output port labeled Joint1,
development, transformation of the COMs from the joint
this port is for the physical connection between the base of
frame to the frame located at the CoG of the bodies is
the robot to the next block.
required. After this transformation and using the concept of
multi-body systems modelling of Simmechanic environment B. Joint block
a model was developed for the UR5 robot. Fig. 6 shows
the Simmechanics blocks used for modelling of the UR5 There are several Joint blocks that are shown in Fig. 6
manipulator with a controller for it. This figure shows the to represent the mechanism of the joints between the robot
Controller and Robot parts. The Robot part contains of three links. Although these blocks are similar, they have different
types of blocks including Base, Joint and Link blocks. The sets of parameter values. The details of the Joint3 block
Controller part is a Matlab function (code) and is not part is illustrated in Fig. 8. For the Joint blocks, there are two
inputs, one for Simmechanics physical connection between
1 https://www.dropbox.com/s/023wlxksrnapx0o/UR5.m?dl=1 parts of the mechanism, which is named Joint3 and the other

SMC_2016 004232
2016 IEEE International Conference on Systems, Man, and Cybernetics • SMC 2016 | October 9-12, 2016 • Budapest, Hungary

one for the torque signal that is applied to the joint refereed
as Tau3 in Fig. 8. There are also two measurement output
signals: q3 and dq3 that are for the joint angle and velocity.
These signals are the system’s states of the joints and they
are useful for control purposes. In the Joint block, the sub-
block Revolute Joint3 is a Simmechanics block of a revolute
joint with its corresponding actuator. The input of this sub- Fig. 10. Graphical result of UR5 modelled in Simmechanics
block is a torque signal that is applied by the control system
(here is controller). The output of the Revolute Joint3 block There are few more parameters, such as links’ radius,
are the joint angle and joint velocity measurement signals selected arbitrarily. These parameters do not have significant
with dimension of radian (rad) and radian per second (rad/s), effect on model’s dynamic performance.We have selected
respectively. Finally, the output of the whole Revolute Joint3 some values by trial and error as there was no reliable source
block is a Simmechanics connection with the name of Link3 for them.
that goes to the Link3 block.
V. VALIDATION S TUDY
In this section the derived mathematical dynamics model
is cross validated by the Simmechanics model of the UR5. To
achieve this goal a controller is designed using the derived
dynamics. Then the output of this controller is applied to
the Simechanics model. By inspecting the response of the
model, the correctness of the derived dynamics is verified.
To achieve this goal, a standard proportional-derivative (PD)
Fig. 8. The robot’s Joint blocks details
controller is used. For this purpose, the inverse dynamic
(feedback linearization) is considered using the outputs of
C. Link block the MATLAB code. Recalling the general form of dynamic
equations of motion of a robot 6 and the inverse dynamic
There are also several Link blocks in Fig. 6 to represent the form 7, and considering the below input:
robot links. The details of the Link3 block is demonstrated in u = M (q)a + C(q, q̇)q̇ + g(q) (11)
Fig. 9. These blocks also have similar structure, hence only
Link3 is explained here. These blocks contain three similar where q is the joint angles, the matrices M (q) and C(q, q̇)
block pairs. Each pair is consisted of a Rigid Transformation and the vector g(q) are elements from the derived dynamics,
block and a Solid block. The middle one is the most and the vector a is a PD controller command defined as a =
important pair especially the Solid block part of it, this q̈ ∗ − KD (q̇ − q̇ ∗ ) − KP (q − q ∗ ). In this control signal, q̈ ∗ ,q̇ ∗
is because it creates a link body that contains the inertia and q ∗ are the desired acceleration, velocity and joint angle
properties of that link. These Link blocks are connected to vectors, respectively, KD and KP are symmetric positive
a joint from its input and a joint from its output, except the definite gain matrices of the derivative and proportional
last Link block. For the Link3, the input of the Link3 is from components of the PD controller. Substituting controller and
the Joint3 and the output of it is applied to the Joint4 see 11 into 7, results to:
Fig. 9. ë + KD ė + KP e = 0 (12)
where ë, ė and e are error signals of acceleration, velocity
and joint angles, respectively.
For the design of the controller parameters, Routh-Hurwitz
criteria was used to obtain the gain matrices. This guarantees
that the errors in 12 will converge to zero from any initial
Fig. 9. The robot’s Link blocks details
condition. Obviously, this convergence is obtainable if the
complete elimination of dynamic nonlinear terms in 7 that
D. Simemchanics model parameters depends on M (q), C(q, q̇)q̇ and g(q) is achieved. In other
words, the derived mathematical dynamics should be the
There are several reports for the parameters of the COMs same as the dynamical properties of Simemechanics model
e.g., [25], [26], one of them is from the manufacturer of of UR5. To show this elimination, we consider a desired
the robot. For the Simmechanics model presented here we position and orientation profile for the UR5 end-effector. We
used the manufacturer parameter. Other specifications, like selected a profile that is singular free and it lies in the robot
DH parameters and inertia properties are from [25]. These workspace. It was observed that the controller Gain matrices
parameters are used for the model and the Simmechanics could be selected as KD = KP = 10I6×6
model is fully obtained. The run of the Simemchanics model The results of the simulation are shown in figures 11.
creates the results shown in Fig. 10. It is observed that the end-effector has tracked the desired

SMC_2016 004233
2016 IEEE International Conference on Systems, Man, and Cybernetics • SMC 2016 | October 9-12, 2016 • Budapest, Hungary

[8] S. Dehghani, H.D. Taghirad, M Darainy, ”Self-tuning Dynamic


Impedance Control for Human Arm Motion”, Biomedical Engineering
(ICBME), 17th Iranian Conference, pp. 1-6, 2010.
[9] F. Aalamifar, R. Khurana, A. Cheng, R. H. Taylor, I. Iordachita, and
E. M. Boctor, ”Enabling technologies for robot assisted ultrasound
tomography: system setup and calibration”, Proc. SPIE 9040, Medical
Imaging 2014: Ultrasonic Imaging and Tomography, Feb 15, 2014.
[10] M. Buding, W. V. Lauer, R. Petrovic, and J. Lim, ”Design of Robotic
Fabricated High Rises, Integrating Robotic Fabrication in a Design
Studio”, Robotic fabrication in Architecture, Art and Design, 2014,
Springer International Publishing, pp. 111-129, 2014.
[11] R. Bloss, ”Innovations like two arms, cheaper prices, easier program-
ming, autonomous and collaborative operation are driving automation
deployment in manufacturing and elsewhere”, Assembly Automation
No. 4, Vol .33, 312-316, 2013.
[12] J. Schrimpf, M. Lind, G. Mathisen, ”Real-time analysis of a multi-
robot sewing cell”, Industrial Technology (ICIT), 2013 IEEE Interna-
tional Conference on, pp. 163-168, Feb 25-28, 2013.
[13] K.R. Guerin, and C. Lea, and C. Paxton, and G.D.Hager, ”A frame-
work for end-user instruction of a robot assistant for manufacturing”,
Proceedings - IEEE International Conference on Robotics and Au-
tomation, pp. 6167-6174, June, 2015.
[14] J. Camillo, ”Robot-mounted vision system simplifies large-part inspec-
Fig. 11. The position and orientation of the end-effector, in Simmechanics tion”, Jounral of Assembly, No. 8, Vol. 58, 2015.
model of the UR5, and their desired signals. [15] K. Hansen, and J. Pedersen, T. Slund, H. Aans, and D. Kraft, ”A
structured light scanner for hyper flexible industrial automation”,
Proceedings - 2014 International Conference on 3D Vision, 3DV 2014,
pp. 401-408, 2015.
position and orientation profiles while all the system’s states [16] A. Weber, ”Human-robot collaboration comes of age”, Journal of
Assembly, No. 2, Vol. 57, 2014.
remian stable . [17] Q. Lei, and M. Wisse, ”Fast grasping of unknown objects using force
balance optimization”, IEEE International Conference on Intelligent
VI. C ONCLUSION Robots and Systems, pp. 2454-2460, 2014.
[18] M. W. Abdullah, H. Routh, M. Weyrich, and J. Wahrburg, ”An Ap-
In this paper, complete modelling of a well-known robotic proach for Peg-in-Hole Assembling using Intuitive Search Algorithm
manipulator UR5 was presented . For this purpose, first the based on Human Behavior and Carried by Sensors Guided Industrial
Robot”, International Federation of Automatic Control (IFAC) 2015,
robot’s kinematic was characterized and calculated. Then its pp. 14761481, 2015.
dynamic properties, inertia matrix, Collioris and centrifu- [19] J. Lim, ”Live robot programming”, Journal Professional Communica-
gal matrix and gravity vector were derived based on the tion, No. 2, Vol. 3, pp. 165-175, 2014.
[20] F. Alambeigi, R. J. Murphy, E. Basafa, R. H. Taylor, and M. Armand,
Langrange method. The derived mathematical model has ”Control of the Coupled Motion of a 6 DoF Robotic Arm and
been implemented in MATLAB. After that, a SimMechanics a Continuum Manipulator for the Treatment of Pelvis Osteolysis”,
model of UR5 was developed with the parameter values Engineering in Medicine and Biology Society (EMBC), 2014 36th
Annual International Conference of the IEEE, pp. 6521-6525, 26-30
obtained from the manufacturer material. At the end, a Aug. 2014.
cross validation of the models was performed by using the [21] M. Lind, ”Automatic Robot Joint Offset Calibration”, Intrnational
mathematical model for the control of Simmechanics model. Workshop of Advanced Manufacturing and Automation, Tapir Aca-
demic Press. 2012.
Through simulation the accuracy of the mathematical model [22] S. Kim, H. J. Kang, A. Cheng, M. A. Lediju Bell, E. Boctor, and
was demonstrated. The models are placed for public access. P. Kazanzides, ”Photoacoustic Image Guidance for Robot-Assisted
Skull Base Surgery”, IEEE International Conference on Robotics and
Automation (ICRA), pp. 592-597, May 26-30, 2015.
R EFERENCES [23] Y. Liu, ”Learning Human Welder Movement in Pipe GTAW: A
Virtualized Welding Approach”, Welding Journal, pp. 388-398, Vol.
[1] www.universal-robots.com
93, 2014.
[2] F. Cheraghpour., S.A.A Moosavian, and A. Nahvi, ”Multiple Aspect
[24] B. Armstrong, O. Khatib, and J. Burdick, The Explicit Dynamic
Grasp performance index for cooperative object manipulation tasks”,
Model and Inertial Parameters of the PUMA 560 Arm, Robotics and
IEEE/ASME Int. Conf. on Advanced Intelligent Mechatronics, pp 386-
Automation, Proceedings, 1986 IEEE International Conference on,
391, 2009.
Vol. 3, pp. 510-518, 1986.
[3] M. Eslamy, S.A.A Moosavian, ”Dynamics and Cooperative object [25] K. Kufieta, ”Force Estimation in Robotic Manipulators: Modeling,
Manipulation Control of Suspended Mobile Manipulators”, J Intell Simulation and Experiments, UR5 as a case study”, a Thesis from
Robot Syst Springer Science+Business Media B.V, pp. 1-19, 2010. Norwegian University of Science and Technology, Department of
[4] K. Harada, K. Kaneko, F. Kanehiro, ”Fast Grasp Planning for Engineering Cybernetics, Jan 29, 2014.
Hand/Arms Systems Based on Convex Model”, IEEE International [26] UR5 Robot User Maunel (2014), version 3.0. Universal Robots A/S.
Conference onRobotics and Automation, pp. 1-7, 2008. [27] M. W. Spong and M. Vidyasagar, ”Robot Dynamics and Control”,
[5] M. Karimi, S.A.A. Moosavian, ”Modified Transpose Effective Jaco- John Wiley & Sons, 2008.
bian Law for Control of Underactuated Manipulators”, Koninklijke [28] J. J. Craig, ”Introduction to Robotics: Mechanics and Control”, Pear-
Brill NY, Leiden and The Robotics Society of Japan, pp. 605-626, son/Prentice Hall Upper Saddle River, NJ, USA, 2005.
2009. [29] K. P. Hawkins, ”Analytic Inverse Kinematics for the Universal Robots
[6] G. Zeng, A. Hemami, ”An overview of robot force control”, Robotica, UR-5/UR-10 Arms”, Technical report, Georgia Institute of Technology
Cambridge University Press, volume 15 ,pp. 473-482, 1997. Publications, Dec 7, 2013.
[7] S.A.A. Moosavian, and E. Papadopoulos, ”Cooperative Object Ma-
nipulation with Contact Impact Using Multiple Impedance Control”,
International Journal of Control, Automation, and Systems, pp 314-
327., 2010.

SMC_2016 004234

You might also like