-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathur.urdf
682 lines (674 loc) · 27 KB
/
ur.urdf
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from ur.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="ur">
<!--
Base UR robot series xacro macro.
NOTE this is NOT a URDF. It cannot directly be loaded by consumers
expecting a flattened '.urdf' file. See the top-level '.xacro' for that
(but note that .xacro must still be processed by the xacro command).
This file models the base kinematic chain of a UR robot, which then gets
parameterised by various configuration files to convert it into a UR3(e),
UR5(e), UR10(e) or UR16e.
NOTE the default kinematic parameters (i.e., link lengths, frame locations,
offsets, etc) do not correspond to any particular robot. They are defaults
only. There WILL be non-zero offsets between the Forward Kinematics results
in TF (i.e., robot_state_publisher) and the values reported by the Teach
Pendant.
For accurate (and robot-specific) transforms, the 'kinematics_parameters_file'
parameter MUST point to a .yaml file containing the appropriate values for
the targeted robot.
If using the UniversalRobots/Universal_Robots_ROS_Driver, follow the steps
described in the readme of that repository to extract the kinematic
calibration from the controller and generate the required .yaml file.
Main author of the migration to yaml configs Ludovic Delval.
Contributors to previous versions (in no particular order)
- Denis Stogl
- Lovro Ivanov
- Felix Messmer
- Kelsey Hawkins
- Wim Meeussen
- Shaun Edwards
- Nadia Hammoudeh Garcia
- Dave Hershberger
- G. vd. Hoorn
- Philip Long
- Dave Coleman
- Miguel Prada
- Mathias Luedtke
- Marcel Schnirring
- Felix von Drigalski
- Felix Exner
- Jimmy Da Silva
- Ajit Krisshna N L
- Muhammad Asif Rana
-->
<!--
NOTE the macro defined in this file is NOT part of the public API of this
package. Users CANNOT rely on this file being available, or stored in
this location. Nor can they rely on the existence of the macro.
-->
<!-- create link fixed to the "world" -->
<link name="world"/>
<ros2_control name="ur" type="system">
<hardware>
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
</hardware>
<joint name="shoulder_pan_joint">
<command_interface name="position">
<param name="min">{-2*pi}</param>
<param name="max">{2*pi}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.15</param>
<param name="max">3.15</param>
</command_interface>
<state_interface name="position">
<!-- initial position for the FakeSystem and simulation -->
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="shoulder_lift_joint">
<command_interface name="position">
<param name="min">{-2*pi}</param>
<param name="max">{2*pi}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.15</param>
<param name="max">3.15</param>
</command_interface>
<state_interface name="position">
<!-- initial position for the FakeSystem and simulation -->
<param name="initial_value">-1.57</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="elbow_joint">
<command_interface name="position">
<param name="min">{-pi}</param>
<param name="max">{pi}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.15</param>
<param name="max">3.15</param>
</command_interface>
<state_interface name="position">
<!-- initial position for the FakeSystem and simulation -->
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="wrist_1_joint">
<command_interface name="position">
<param name="min">{-2*pi}</param>
<param name="max">{2*pi}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.2</param>
<param name="max">3.2</param>
</command_interface>
<state_interface name="position">
<!-- initial position for the FakeSystem and simulation -->
<param name="initial_value">-1.57</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="wrist_2_joint">
<command_interface name="position">
<param name="min">{-2*pi}</param>
<param name="max">{2*pi}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.2</param>
<param name="max">3.2</param>
</command_interface>
<state_interface name="position">
<!-- initial position for the FakeSystem and simulation -->
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<joint name="wrist_3_joint">
<command_interface name="position">
<param name="min">{-2*pi}</param>
<param name="max">{2*pi}</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-3.2</param>
<param name="max">3.2</param>
</command_interface>
<state_interface name="position">
<!-- initial position for the FakeSystem and simulation -->
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
</ros2_control>
<!-- Add URDF transmission elements (for ros_control) -->
<!--<xacro:ur_arm_transmission prefix="${prefix}" hw_interface="${transmission_hw_interface}" />-->
<!-- Placeholder for ros2_control transmission which don't yet exist -->
<!-- links - main serial chain -->
<link name="base_link"/>
<link name="base_link_inertia">
<visual>
<origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/ur_description/share/ur_description/meshes/ur3e/visual/base.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/ur_description/share/ur_description/meshes/ur3e/collision/base.stl"/>
</geometry>
</collision>
<inertial>
<mass value="2.0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.0030531654454" ixy="0.0" ixz="0.0" iyy="0.0030531654454" iyz="0.0" izz="0.005625"/>
</inertial>
</link>
<link name="shoulder_link">
<visual>
<origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/ur_description/share/ur_description/meshes/ur3e/visual/shoulder.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/ur_description/share/ur_description/meshes/ur3e/collision/shoulder.stl"/>
</geometry>
</collision>
<inertial>
<mass value="2.0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.008093163429399999" ixy="0.0" ixz="0.0" iyy="0.008093163429399999" iyz="0.0" izz="0.005625"/>
</inertial>
</link>
<link name="upper_arm_link">
<visual>
<origin rpy="1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0.12"/>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/ur_description/share/ur_description/meshes/ur3e/visual/upperarm.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0.12"/>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/ur_description/share/ur_description/meshes/ur3e/collision/upperarm.stl"/>
</geometry>
</collision>
<inertial>
<mass value="3.42"/>
<origin rpy="0 1.5707963267948966 0" xyz="-0.121825 0.0 0.12"/>
<inertia ixx="0.021728483221103233" ixy="0.0" ixz="0.0" iyy="0.021728483221103233" iyz="0.0" izz="0.00961875"/>
</inertial>
</link>
<link name="forearm_link">
<visual>
<origin rpy="1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0.027"/>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/ur_description/share/ur_description/meshes/ur3e/visual/forearm.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 -1.5707963267948966" xyz="0 0 0.027"/>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/ur_description/share/ur_description/meshes/ur3e/collision/forearm.stl"/>
</geometry>
</collision>
<inertial>
<mass value="1.26"/>
<origin rpy="0 1.5707963267948966 0" xyz="-0.1066 0.0 0.027"/>
<inertia ixx="0.0065445675821719194" ixy="0.0" ixz="0.0" iyy="0.0065445675821719194" iyz="0.0" izz="0.00354375"/>
</inertial>
</link>
<link name="wrist_1_link">
<visual>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 -0.104"/>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/ur_description/share/ur_description/meshes/ur3e/visual/wrist1.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 -0.104"/>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/ur_description/share/ur_description/meshes/ur3e/collision/wrist1.stl"/>
</geometry>
</collision>
<inertial>
<mass value="0.8"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.002084999166" ixy="0.0" ixz="0.0" iyy="0.002084999166" iyz="0.0" izz="0.00225"/>
</inertial>
</link>
<link name="wrist_2_link">
<visual>
<origin rpy="0 0 0" xyz="0 0 -0.08535"/>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/ur_description/share/ur_description/meshes/ur3e/visual/wrist2.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.08535"/>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/ur_description/share/ur_description/meshes/ur3e/collision/wrist2.stl"/>
</geometry>
</collision>
<inertial>
<mass value="0.8"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.002084999166" ixy="0.0" ixz="0.0" iyy="0.002084999166" iyz="0.0" izz="0.00225"/>
</inertial>
</link>
<link name="wrist_3_link">
<visual>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 -0.0921"/>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/ur_description/share/ur_description/meshes/ur3e/visual/wrist3.dae"/>
</geometry>
</visual>
<collision>
<origin rpy="1.5707963267948966 0 0" xyz="0 0 -0.0921"/>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/ur_description/share/ur_description/meshes/ur3e/collision/wrist3.stl"/>
</geometry>
</collision>
<inertial>
<mass value="0.35"/>
<origin rpy="0 0 0" xyz="0.0 0.0 -0.02"/>
<inertia ixx="0.00013626661215999998" ixy="0.0" ixz="0.0" iyy="0.00013626661215999998" iyz="0.0" izz="0.0001792"/>
</inertial>
</link>
<!-- base_joint fixes base_link to the environment -->
<joint name="base_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0"/>
<parent link="world"/>
<child link="base_link"/>
</joint>
<!-- joints - main serial chain -->
<joint name="base_link-base_link_inertia" type="fixed">
<parent link="base_link"/>
<child link="base_link_inertia"/>
<!-- 'base_link' is REP-103 aligned (so X+ forward), while the internal
frames of the robot/controller have X+ pointing backwards.
Use the joint between 'base_link' and 'base_link_inertia' (a dummy
link/frame) to introduce the necessary rotation over Z (of pi rad).
-->
<origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
</joint>
<joint name="shoulder_pan_joint" type="revolute">
<parent link="base_link_inertia"/>
<child link="shoulder_link"/>
<origin rpy="0 0 0" xyz="0 0 0.15185"/>
<axis xyz="0 0 1"/>
<limit effort="56.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.141592653589793"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="shoulder_lift_joint" type="revolute">
<parent link="shoulder_link"/>
<child link="upper_arm_link"/>
<origin rpy="1.570796327 0 0" xyz="0 0 0"/>
<axis xyz="0 0 1"/>
<limit effort="56.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="3.141592653589793"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="elbow_joint" type="revolute">
<parent link="upper_arm_link"/>
<child link="forearm_link"/>
<origin rpy="0 0 0" xyz="-0.24355 0 0"/>
<axis xyz="0 0 1"/>
<limit effort="28.0" lower="-3.141592653589793" upper="3.141592653589793" velocity="3.141592653589793"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="wrist_1_joint" type="revolute">
<parent link="forearm_link"/>
<child link="wrist_1_link"/>
<origin rpy="0 0 0" xyz="-0.2132 0 0.13105"/>
<axis xyz="0 0 1"/>
<limit effort="12.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="6.283185307179586"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="wrist_2_joint" type="revolute">
<parent link="wrist_1_link"/>
<child link="wrist_2_link"/>
<origin rpy="1.570796327 0 0" xyz="0 -0.08535 -1.750557762378351e-11"/>
<axis xyz="0 0 1"/>
<limit effort="12.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="6.283185307179586"/>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="wrist_3_joint" type="revolute">
<parent link="wrist_2_link"/>
<child link="wrist_3_link"/>
<origin rpy="1.570796326589793 3.141592653589793 3.141592653589793" xyz="0 0.0921 -1.8890025766262e-11"/>
<axis xyz="0 0 1"/>
<limit effort="12.0" lower="-6.283185307179586" upper="6.283185307179586" velocity="6.283185307179586"/>
<dynamics damping="0" friction="0"/>
</joint>
<link name="ft_frame"/>
<joint name="wrist_3_link-ft_frame" type="fixed">
<parent link="wrist_3_link"/>
<child link="ft_frame"/>
<origin rpy="3.141592653589793 0 0" xyz="0 0 0"/>
</joint>
<!-- ROS-Industrial 'base' frame - base_link to UR 'Base' Coordinates transform -->
<link name="base"/>
<joint name="base_link-base_fixed_joint" type="fixed">
<!-- Note the rotation over Z of pi radians - as base_link is REP-103
aligned (i.e., has X+ forward, Y+ left and Z+ up), this is needed
to correctly align 'base' with the 'Base' coordinate system of
the UR controller.
-->
<origin rpy="0 0 3.141592653589793" xyz="0 0 0"/>
<parent link="base_link"/>
<child link="base"/>
</joint>
<!-- ROS-Industrial 'flange' frame - attachment point for EEF models -->
<link name="flange"/>
<joint name="wrist_3-flange" type="fixed">
<parent link="wrist_3_link"/>
<child link="flange"/>
<origin rpy="0 -1.5707963267948966 -1.5707963267948966" xyz="0 0 0"/>
</joint>
<!-- ROS-Industrial 'tool0' frame - all-zeros tool frame -->
<link name="tool0"/>
<joint name="flange-tool0" type="fixed">
<!-- default toolframe - X+ left, Y+ up, Z+ front -->
<origin rpy="1.5707963267948966 0 1.5707963267948966" xyz="0 0 0"/>
<parent link="flange"/>
<child link="tool0"/>
</joint>
<!-- Gazebo plugins -->
<gazebo reference="world">
</gazebo>
<gazebo>
<plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
<parameters></parameters>
</plugin>
</gazebo>
<ros2_control name="RobotiqGripperHardwareInterface" type="system">
<!-- Plugins -->
<hardware>
<!-- Set use_dummy to true to connect to a dummy driver for testing purposes. -->
<param name="use_dummy">false</param>
<plugin>robotiq_driver/RobotiqGripperHardwareInterface</plugin>
<param name="gripper_closed_position">0.7929</param>
<param name="COM_port">/dev/ttyUSB0</param>
<param name="gripper_speed_multiplier">1.0</param>
<param name="gripper_force_multiplier">0.5</param>
</hardware>
<!-- Joint interfaces -->
<!-- With Ignition or Hardware, they handle mimic joints, so we only need this command interface activated -->
<joint name="robotiq_85_left_knuckle_joint">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">0.7929</param>
</state_interface>
<state_interface name="velocity"/>
</joint>
<gpio name="reactivate_gripper">
<command_interface name="reactivate_gripper_cmd"/>
<command_interface name="reactivate_gripper_response"/>
</gpio>
</ros2_control>
<link name="robotiq_85_base_link">
<visual>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/robotiq_description/share/robotiq_description/meshes/visual/2f_85/robotiq_base.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/robotiq_description/share/robotiq_description/meshes/collision/2f_85/robotiq_base.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.0 2.274e-05 0.03232288"/>
<mass value="6.6320197e-01"/>
<inertia ixx="5.1617816e-04" ixy="2.936e-8" ixz="0.0" iyy="5.8802208e-04" iyz="-3.2296e-7" izz="3.9462776e-04"/>
</inertial>
<parent link="tool0"/>
</link>
<link name="robotiq_85_left_knuckle_link">
<visual>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/robotiq_description/share/robotiq_description/meshes/visual/2f_85/left_knuckle.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/robotiq_description/share/robotiq_description/meshes/collision/2f_85/left_knuckle.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.01213197 0.0002 -0.00058647"/>
<mass value="1.384773208e-02"/>
<inertia ixx="3.5232e-7" ixy="0.0" ixz="1.1744e-7" iyy="2.31944e-6" iyz="0" izz="2.23136e-6"/>
</inertial>
</link>
<link name="robotiq_85_right_knuckle_link">
<visual>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/robotiq_description/share/robotiq_description/meshes/visual/2f_85/right_knuckle.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/robotiq_description/share/robotiq_description/meshes/collision/2f_85/right_knuckle.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.01213197 0.0002 -0.00058647"/>
<mass value="1.384773208e-02"/>
<inertia ixx="3.5232e-7" ixy="0.0" ixz="-1.1744e-7" iyy="2.31944e-6" iyz="0.0" izz="2.23136e-6"/>
</inertial>
</link>
<link name="robotiq_85_left_finger_link">
<visual>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/robotiq_description/share/robotiq_description/meshes/visual/2f_85/left_finger.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/robotiq_description/share/robotiq_description/meshes/collision/2f_85/left_finger.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.00346899 -0.00079447 0.01867121"/>
<mass value="4.260376752e-02"/>
<inertia ixx="1.385792000000000e-05" ixy="0.0" ixz="-2.17264e-06" iyy="1.183208e-05" iyz="0.0" izz="5.19672e-06"/>
</inertial>
</link>
<link name="robotiq_85_right_finger_link">
<visual>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/robotiq_description/share/robotiq_description/meshes/visual/2f_85/right_finger.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/robotiq_description/share/robotiq_description/meshes/collision/2f_85/right_finger.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.00346899 -5.53e-06 0.01867121"/>
<mass value="4.260376752000000e-02"/>
<inertia ixx="1.385792e-05" ixy="0.0" ixz="2.17264e-06" iyy="1.183208e-05" iyz="0.0" izz="5.19672e-06"/>
</inertial>
</link>
<link name="robotiq_85_left_inner_knuckle_link">
<visual>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/robotiq_description/share/robotiq_description/meshes/visual/2f_85/left_inner_knuckle.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/robotiq_description/share/robotiq_description/meshes/collision/2f_85/left_inner_knuckle.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.01897699 0.00015001 0.02247101"/>
<mass value="2.969376448e-02"/>
<inertia ixx="9.57136e-06" ixy="0.0" ixz="-3.93424e-06" iyy="8.69056e-06" iyz="0.0" izz="8.19144e-06"/>
</inertial>
</link>
<link name="robotiq_85_right_inner_knuckle_link">
<visual>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/robotiq_description/share/robotiq_description/meshes/visual/2f_85/right_inner_knuckle.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/robotiq_description/share/robotiq_description/meshes/collision/2f_85/right_inner_knuckle.stl"/>
</geometry>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.01926824 5.001e-05 0.02222178"/>
<mass value="2.969376448e-02"/>
<inertia ixx="9.42456e-06" ixy="0.0" ixz="3.9636e-06" iyy="8.69056e-06" iyz="0.0" izz="8.33824e-06"/>
</inertial>
</link>
<link name="robotiq_85_left_finger_tip_link">
<visual>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/robotiq_description/share/robotiq_description/meshes/visual/2f_85/left_finger_tip.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/robotiq_description/share/robotiq_description/meshes/collision/2f_85/left_finger_tip.stl"/>
</geometry>
<surface>
<friction>
<ode>
<mu1>100000.0</mu1>
<mu2>100000.0</mu2>
</ode>
</friction>
<contact>
<ode>
<kp>1e+5</kp>
<kd>1</kd>
<soft_cfm>0</soft_cfm>
<soft_erp>0.2</soft_erp>
<minDepth>0.002</minDepth>
<maxVel>0</maxVel>
</ode>
</contact>
</surface>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="-0.01456706 -0.0008 0.01649701"/>
<mass value="4.268588744e-02"/>
<inertia ixx="1.048152e-05" ixy="0.0" ixz="3.5232e-6" iyy="1.197888e-05" iyz="0.0" izz="4.22784e-06"/>
</inertial>
</link>
<link name="robotiq_85_right_finger_tip_link">
<visual>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/robotiq_description/share/robotiq_description/meshes/visual/2f_85/right_finger_tip.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="file:///home/oj/ur3_ws/install/robotiq_description/share/robotiq_description/meshes/collision/2f_85/right_finger_tip.stl"/>
</geometry>
<surface>
<friction>
<ode>
<mu1>100000.0</mu1>
<mu2>100000.0</mu2>
</ode>
</friction>
<contact>
<ode>
<kp>1e+5</kp>
<kd>1</kd>
<soft_cfm>0</soft_cfm>
<soft_erp>0.2</soft_erp>
<minDepth>0.002</minDepth>
<maxVel>0</maxVel>
</ode>
</contact>
</surface>
</collision>
<inertial>
<origin rpy="0 0 0" xyz="0.01456706 5e-05 0.01649701"/>
<mass value="4.268588744e-02"/>
<inertia ixx="1.048152e-05" ixy="0.0" ixz="-3.5232e-06" iyy="1.197888e-05" iyz="0.0" izz="4.22784e-06"/>
</inertial>
</link>
<joint name="robotiq_85_base_joint" type="fixed">
<parent link="tool0"/>
<child link="robotiq_85_base_link"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
</joint>
<joint name="robotiq_85_left_knuckle_joint" type="revolute">
<parent link="robotiq_85_base_link"/>
<child link="robotiq_85_left_knuckle_link"/>
<axis xyz="0 -1 0"/>
<origin rpy="0 0 0" xyz="0.03060114 0.0 0.05490452"/>
<limit effort="50" lower="0.0" upper="0.8" velocity="0.5"/>
</joint>
<joint name="robotiq_85_right_knuckle_joint" type="revolute">
<parent link="robotiq_85_base_link"/>
<child link="robotiq_85_right_knuckle_link"/>
<axis xyz="0 -1 0"/>
<origin rpy="0 0 0" xyz="-0.03060114 0.0 0.05490452"/>
<limit effort="50" lower="-0.8" upper="0.0" velocity="0.5"/>
<mimic joint="robotiq_85_left_knuckle_joint" multiplier="-1"/>
</joint>
<joint name="robotiq_85_left_finger_joint" type="fixed">
<parent link="robotiq_85_left_knuckle_link"/>
<child link="robotiq_85_left_finger_link"/>
<origin rpy="0 0 0" xyz="0.03152616 0.0 -0.00376347"/>
</joint>
<joint name="robotiq_85_right_finger_joint" type="fixed">
<parent link="robotiq_85_right_knuckle_link"/>
<child link="robotiq_85_right_finger_link"/>
<origin rpy="0 0 0" xyz="-0.03152616 0.0 -0.00376347"/>
</joint>
<joint name="robotiq_85_left_inner_knuckle_joint" type="continuous">
<parent link="robotiq_85_base_link"/>
<child link="robotiq_85_left_inner_knuckle_link"/>
<axis xyz="0 -1 0"/>
<origin rpy="0 0 0" xyz="0.0127 0.0 0.06142"/>
<mimic joint="robotiq_85_left_knuckle_joint"/>
</joint>
<joint name="robotiq_85_right_inner_knuckle_joint" type="continuous">
<parent link="robotiq_85_base_link"/>
<child link="robotiq_85_right_inner_knuckle_link"/>
<axis xyz="0 -1 0"/>
<origin rpy="0 0 0" xyz="-0.0127 0.0 0.06142"/>
<mimic joint="robotiq_85_left_knuckle_joint" multiplier="-1"/>
</joint>
<joint name="robotiq_85_left_finger_tip_joint" type="continuous">
<parent link="robotiq_85_left_finger_link"/>
<child link="robotiq_85_left_finger_tip_link"/>
<axis xyz="0 -1 0"/>
<origin rpy="0 0 0" xyz="0.00563134 0.0 0.04718515"/>
<mimic joint="robotiq_85_left_knuckle_joint" multiplier="-1"/>
</joint>
<joint name="robotiq_85_right_finger_tip_joint" type="continuous">
<parent link="robotiq_85_right_finger_link"/>
<child link="robotiq_85_right_finger_tip_link"/>
<axis xyz="0 -1 0"/>
<origin rpy="0 0 0" xyz="-0.00563134 0.0 0.04718515"/>
<mimic joint="robotiq_85_left_knuckle_joint"/>
</joint>
<!--END ========================= OJU added Gripper ===================-->
</robot>