UR5 modeling

157 views
Skip to first unread message

Hesam Jafarian

unread,
Dec 13, 2018, 2:56:18 PM12/13/18
to Robotics & Machine Vision Toolboxes
Dear Peter and all,
I am modeling a UR5 robot using the standard DH.
The DH is retrievable on the following link.
The problem I have at the moment is that when I apply the standard DH I get the positions very well. However, for the orientation of Forward Kinematics the angles are not very well aligned with the simulator provided by the universal-robots.

I am just using the following code 


 L(1)=Link([0,  0,      0,              pi/2])
 L(2)=Link([0,  0,      -425,              0])
 L(3)=Link([0,  0,      -392.25,           0])
 L(4)=Link([0,  109.15, 0,              pi/2])
 L(5)=Link([0,  94.65,  0,             -pi/2])
 L(6)=Link([0,  82.3,   0,                 0])
 
UR5_robot=SerialLink(L,'name','UR5');

Ttool=transl([0,0,0]);
UR5_robot.tool=Ttool;

Tbase=transl([0,0,89.159]);
UR5_robot.base= Tbase;


UR5_robot.fkine([0,0,0,0,0,0])

%%plot 
W = [-1100 1100 -1100 1100 -1200 1200];
UR5_robot.teach([0 0 0 0 0 0 ], 'workspace',W)
UR5_robot.plot([0,0,0,0,0,0])
waitforbuttonpress
UR5_robot.teach([0 -pi/2 0 -pi/2 0 0 ], 'workspace',W)
UR5_robot.plot([0,-pi/2,0,-pi/2,0,0])

My questions is that is there any reason the angles illustrated in the RoboticToolbox does not match for that. Should I add any option or so?

Peter Corke

unread,
Dec 15, 2018, 6:39:16 PM12/15/18
to Robotics & Machine Vision Toolboxes
Hi Hesam,

I don't have the UR simulator so I need you to be much more specific about where the discrepancy is.  For your FK example I get an end effector pose of

ans = 
         1         0         0    -817.2
         0         0        -1    -191.5
         0         1         0    -5.491
         0         0         0         1
>> 

what does the simulator say the orientation is?

Note there is already a UR5 model in RTB, see mdl_ur5.

peter
Reply all
Reply to author
Forward
0 new messages