-
Notifications
You must be signed in to change notification settings - Fork 6
/
pr2.urdf
4058 lines (4054 loc) · 151 KB
/
pr2.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
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from robots/pr2.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="pr2" xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" xmlns:joint="http://playerstage.sourceforge.net/gazebo/xmlschema/#slider" xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor" xmlns:xacro="http://ros.org/wiki/xacro">
<!-- The following included files set up definitions of parts of the robot body -->
<!-- misc common stuff? -->
<!-- Gear Ratio Corrections: Divide transmission reductions by these factors (Nominally 1)-->
<!-- ********** Right Arm ********** -->
<!-- Flag offsets: Add to the optical flag locations (Nominally 0) -->
<!-- ********** Head ********** -->
<!-- Head Location: Add to the transform from torso to head_pan_link (Nominally 0) -->
<!-- Flag Offsets -->
<!-- Casters -->
<!-- Stereo Camera Location (Nominally 0) -->
<!-- Kinect Camera Location (Nominally 0) -->
<!-- HighDef Camera Location (Nominally 0) -->
<!-- Throwing in left arm constants to appease the xacro parser -->
<!-- PR2 Arm -->
<!-- Things that are needed only for Gazebo (not the physical robot). These include
sensor and controller plugin specifications -->
<!-- Upperarm roll: internal fixed attchment point for upper arm -->
<!-- Gear Ratio Corrections: Divide transmission reductions by these factors (Nominally 1)-->
<!-- ********** Right Arm ********** -->
<!-- Flag offsets: Add to the optical flag locations (Nominally 0) -->
<!-- ********** Head ********** -->
<!-- Head Location: Add to the transform from torso to head_pan_link (Nominally 0) -->
<!-- Flag Offsets -->
<!-- Casters -->
<!-- Stereo Camera Location (Nominally 0) -->
<!-- Kinect Camera Location (Nominally 0) -->
<!-- HighDef Camera Location (Nominally 0) -->
<!-- Throwing in left arm constants to appease the xacro parser -->
<!--TODO Define and give source-->
<!--TODO Define and give source-->
<!-- ============================ Shoulder ============================ -->
<!-- Upperarm roll: internal fixed attchment point for upper arm -->
<!-- Things that are needed only for Gazebo (not the physical robot). These include
sensor and controller plugin specifications -->
<!-- Elbow flex -->
<!-- Forearm roll -->
<!-- ============================ Upper Arm ============================ -->
<!-- Forearm roll -->
<!-- Gear Ratio Corrections: Divide transmission reductions by these factors (Nominally 1)-->
<!-- ********** Right Arm ********** -->
<!-- Flag offsets: Add to the optical flag locations (Nominally 0) -->
<!-- ********** Head ********** -->
<!-- Head Location: Add to the transform from torso to head_pan_link (Nominally 0) -->
<!-- Flag Offsets -->
<!-- Casters -->
<!-- Stereo Camera Location (Nominally 0) -->
<!-- Kinect Camera Location (Nominally 0) -->
<!-- HighDef Camera Location (Nominally 0) -->
<!-- Throwing in left arm constants to appease the xacro parser -->
<!-- Inertial properties differ slightly for left vs right arm -->
<!-- ============================ Upper Arm ============================ -->
<!-- Includes elbow flex, FA roll joints in macros below -->
<!-- FA roll joint only -->
<!-- Things that are needed only for Gazebo (not the physical robot). These include
sensor and controller plugin specifications -->
<!-- Gear Ratio Corrections: Divide transmission reductions by these factors (Nominally 1)-->
<!-- ********** Right Arm ********** -->
<!-- Flag offsets: Add to the optical flag locations (Nominally 0) -->
<!-- ********** Head ********** -->
<!-- Head Location: Add to the transform from torso to head_pan_link (Nominally 0) -->
<!-- Flag Offsets -->
<!-- Casters -->
<!-- Stereo Camera Location (Nominally 0) -->
<!-- Kinect Camera Location (Nominally 0) -->
<!-- HighDef Camera Location (Nominally 0) -->
<!-- Throwing in left arm constants to appease the xacro parser -->
<!-- ============================ Forearm ============================ -->
<!-- PR2 gripper -->
<!-- PR2 head -->
<!-- PR2 tilting laser mount -->
<!-- PR2 torso -->
<!-- PR2 base -->
<!-- Caster wheel transmission -->
<!-- Hub transmission only -->
<!-- DATA SOURCES -->
<!-- all link offsets, CG, limits are obtained from Function Engineering spreadsheet 090224_link_data.xls unless stated otherwise -->
<!-- all link geometry sizes are obtained from Function provided CAD model unless stated otherwise -->
<!-- all simplified collision geometry are hand approximated from CAD model, sometimes from respective bounding boxes -->
<!-- This is the 'effective' wheel radius. Wheel radius for uncompressed wheel is 0.079. mp 20080801 -->
<!-- simplified box collision geometry for base -->
<!-- simplified box collision geometry for hokuyo laser -->
<!-- -->
<!-- wheel -->
<!-- -->
<!-- Macro for PR2 Caster hub only -->
<!-- The xacro macro xacro:pr2_base contains: base, casters and wheels -->
<!-- Head sensors -->
<!-- This urdf macro defines following sensors:
prosilica
double stereo camera
-->
<!-- Made by Kevin for A2 sensor package -->
<!-- Origin is center mount screw on sensor plate mount -->
<!-- When mounted properly, should have same origin as head plate frame -->
<!-- Made by Kevin for double stereo camera for PR-2 Beta. -->
<!-- Needs calibration verification, and CAD check. -->
<!-- stereo camera macro uses wge100_camera macros -->
<!-- hack_baseline is used to simulate right stereo camera projection matrix translation to left stereo camera frame, currently on the hardware,
custom left stereo camera frame_id is passed to right stereo wge100 camera node at launch time, baseline is stored on the camera. -->
<!-- this macro is used for creating wide and narrow double stereo camera in simulation -->
<!-- +y to the left -->
<!-- this macro is used for creating wide and narrow double stereo camera links -->
<!-- Made by Kevin for double stereo camera for PR-2 Beta. -->
<!-- Needs calibration verification, and CAD check. -->
<!-- Made by Kevin for A2 sensor package -->
<!-- Origin is center mount screw on sensor plate mount -->
<!-- When mounted properly, should have same origin as head plate frame -->
<!-- Camera sensors -->
<!-- hack_baseline is used to simulate right stereo camera projection matrix translation to left stereo camera frame, currently on the hardware,
custom left stereo camera frame_id is passed to right stereo wge100 camera node at launch time, baseline is stored on the camera. -->
<!-- Texture projector -->
<!-- this controller is pushed into a body scope (previously model scope)
this will only work with added r36415 patch in simulator_gazebo stack
otherwise projector will not work without removing the reference tag -->
<!-- generic simulator_gazebo plugins for starting mechanism control, ros time, ros battery -->
<gazebo>
<plugin filename="libgazebo_ros_controller_manager.so" name="gazebo_ros_controller_manager">
<alwaysOn>true</alwaysOn>
<updateRate>1000.0</updateRate>
</plugin>
<plugin filename="libgazebo_ros_power_monitor.so" name="gazebo_ros_power_monitor_controller">
<alwaysOn>true</alwaysOn>
<updateRate>1.0</updateRate>
<timeout>5</timeout>
<powerStateTopic>power_state</powerStateTopic>
<powerStateRate>10.0</powerStateRate>
<fullChargeCapacity>87.78</fullChargeCapacity>
<dischargeRate>-474</dischargeRate>
<chargeRate>525</chargeRate>
<dischargeVoltage>15.52</dischargeVoltage>
<chargeVoltage>16.41</chargeVoltage>
</plugin>
</gazebo>
<!-- materials for visualization -->
<material name="Blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
<material name="Green">
<color rgba="0.0 0.8 0.0 1.0"/>
</material>
<material name="Grey">
<color rgba="0.7 0.7 0.7 1.0"/>
</material>
<material name="Grey2">
<color rgba="0.9 0.9 0.9 1.0"/>
</material>
<material name="Red">
<color rgba="0.8 0.0 0.0 1.0"/>
</material>
<material name="White">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
<material name="Black">
<color rgba="0.1 0.1 0.1 1.0"/>
</material>
<material name="LightGrey">
<color rgba="0.6 0.6 0.6 1.0"/>
</material>
<material name="Caster">
<texture filename="materials/textures/pr2_caster_texture.png"/>
</material>
<material name="Wheel_l">
<texture filename="materials/textures/pr2_wheel_left.png"/>
</material>
<material name="Wheel_r">
<texture filename="materials/textures/pr2_wheel_right.png"/>
</material>
<material name="RollLinks">
<texture filename="materials/textures/pr2_wheel_left.png"/>
</material>
<!-- Caelan: adapted from drake/pr2_simplified.urdf -->
<link name="world_link"/>
<link name="base_link_0"/>
<link name="base_link_1"/>
<joint name="x" type="prismatic">
<limit lower="-5" upper="5"/>
<parent link="world_link"/>
<child link="base_link_0"/>
<axis xyz="1 0 0"/>
</joint>
<joint name="y" type="prismatic">
<limit lower="-5" upper="5"/>
<parent link="base_link_0"/>
<child link="base_link_1"/>
<axis xyz="0 1 0"/>
</joint>
<joint name="theta" type="continuous">
<parent link="base_link_1"/>
<child link="base_footprint"/>
<axis xyz="0 0 1"/>
</joint>
<transmission name="x_transmission" type="SimpleTransmission">
<actuator name="x_motor"/>
<joint name="x"/>
<mechanicalReduction>-70000.0</mechanicalReduction>
</transmission>
<transmission name="y_transmission" type="SimpleTransmission">
<actuator name="y_motor"/>
<joint name="y"/>
<mechanicalReduction>-70000.0</mechanicalReduction>
</transmission>
<transmission name="theta_transmission" type="SimpleTransmission">
<actuator name="theta_motor"/>
<joint name="theta"/>
<mechanicalReduction>-70000.0</mechanicalReduction>
</transmission>
<!-- Now we can start using the macros included above to define the actual PR2 -->
<!-- The first use of a macro. This one was defined in base.urdf.xacro above.
A macro like this will expand to a set of link and joint definitions, and to additional
Gazebo-related extensions (sensor plugins, etc). The macro takes an argument, name,
that equals "base", and uses it to generate names for its component links and joints
(e.g., base_link). The included origin block is also an argument to the macro. By convention,
the origin block defines where the component is w.r.t its parent (in this case the parent
is the world frame). For more, see http://www.ros.org/wiki/xacro -->
<link name="base_link">
<inertial>
<mass value="116.0"/>
<origin xyz="-0.061 0.0 0.1465"/>
<inertia ixx="5.652232699207" ixy="-0.009719934438" ixz="1.293988226423" iyy="5.669473158652" iyz="-0.007379583694" izz="3.683196351726"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/base_v0/base.dae"/>
</geometry>
<material name="White"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/base_v0/base_L.stl"/>
</geometry>
</collision>
</link>
<!-- base_footprint is a fictitious link(frame) that is on the ground right below base_link origin,
navigation stack depends on this frame -->
<link name="base_footprint">
<inertial>
<mass value="1.0"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.01 0.01 0.01"/>
</geometry>
<material name="White"/>
</visual>
<collision>
<!-- represent base collision with a simple rectangular model, positioned by base_size_z s.t. top
surface of the collision box matches the top surface of the PR2 base -->
<origin rpy="0 0 0" xyz="0 0 0.071"/>
<geometry>
<box size="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<joint name="base_footprint_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.051"/>
<child link="base_link"/>
<parent link="base_footprint"/>
</joint>
<!-- visualize bellow -->
<link name="base_bellow_link">
<inertial>
<mass value="1.0"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.05 0.37 0.3"/>
</geometry>
<material name="Black"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="0.05 0.37 0.3"/>
</geometry>
</collision>
</link>
<joint name="base_bellow_joint" type="fixed">
<origin rpy="0 0 0" xyz="-0.29 0 0.8"/>
<parent link="base_link"/>
<child link="base_bellow_link"/>
</joint>
<!-- base laser -->
<joint name="base_laser_joint" type="fixed">
<axis xyz="0 1 0"/>
<origin rpy="0 0 0" xyz="0.275 0.0 0.252"/>
<parent link="base_link"/>
<child link="base_laser_link"/>
</joint>
<link name="base_laser_link" type="laser">
<inertial>
<mass value="0.001"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.000001" iyz="0" izz="0.0001"/>
</inertial>
</link>
<!-- gazebo extensions -->
<gazebo reference="base_laser_link">
<sensor name="base_laser" type="ray">
<always_on>true</always_on>
<update_rate>20</update_rate>
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<ray>
<scan>
<horizontal>
<samples>640</samples>
<resolution>1</resolution>
<min_angle>-2.2689</min_angle>
<max_angle>2.2689</max_angle>
</horizontal>
</scan>
<range>
<min>0.08</min>
<max>10.0</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin filename="libgazebo_ros_laser.so" name="gazebo_ros_base_laser_controller">
<gaussianNoise>0.005</gaussianNoise>
<alwaysOn>true</alwaysOn>
<updateRate>20</updateRate>
<topicName>base_scan</topicName>
<frameName>base_laser_link</frameName>
<hokuyoMinIntensity>101</hokuyoMinIntensity>
</plugin>
</sensor>
</gazebo>
<!-- all four caster macros -->
<joint name="fl_caster_rotation_joint" type="continuous">
<axis xyz="0 0 1"/>
<limit effort="6.5" velocity="10"/>
<!-- alpha tested velocity and effort limits -->
<safety_controller k_velocity="10"/>
<calibration rising="-0.785398163397"/>
<dynamics damping="1.0" friction="0.0"/>
<origin rpy="0 0 0" xyz="0.2246 0.2246 0.0282"/>
<parent link="base_link"/>
<child link="fl_caster_rotation_link"/>
</joint>
<link name="fl_caster_rotation_link">
<inertial>
<mass value="3.473082"/>
<origin xyz="0 0 0.07"/>
<inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983" iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/base_v0/caster.stl"/>
</geometry>
<material name="Caster"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/base_v0/caster_L.stl"/>
</geometry>
</collision>
</link>
<!-- extensions -->
<transmission name="fl_caster_rotation_trans" type="pr2_mechanism_model/SimpleTransmission">
<actuator name="fl_caster_rotation_motor"/>
<joint name="fl_caster_rotation_joint"/>
<mechanicalReduction>-79.2380952381</mechanicalReduction>
</transmission>
<!-- wheel macros -->
<joint name="fl_caster_l_wheel_joint" type="continuous">
<axis xyz="0 1 0"/>
<limit effort="7" velocity="15"/>
<!-- alpha tested effort and velocity limits -->
<safety_controller k_velocity="10"/>
<dynamics damping="1.0" friction="0.0"/>
<origin rpy="0 0 0" xyz="0 0.049 0"/>
<parent link="fl_caster_rotation_link"/>
<child link="fl_caster_l_wheel_link"/>
</joint>
<link name="fl_caster_l_wheel_link">
<inertial>
<mass value="0.44036"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983" iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/base_v0/wheel.dae"/>
</geometry>
<material name="Wheel_l"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<!-- rotation because cyl. geom primitive has symmetry axis in +x direction -->
<geometry>
<cylinder length="0.034" radius="0.074792"/>
</geometry>
</collision>
</link>
<!-- extensions -->
<gazebo reference="fl_caster_l_wheel_link">
<mu1 value="100.0"/>
<mu2 value="100.0"/>
<kp value="1000000.0"/>
<kd value="1.0"/>
<maxVel value="100.0"/>
<minDepth value="0.0"/>
</gazebo>
<transmission name="fl_caster_l_wheel_trans" type="pr2_mechanism_model/SimpleTransmission">
<actuator name="fl_caster_l_wheel_motor"/>
<joint name="fl_caster_l_wheel_joint"/>
<mechanicalReduction>79.2380952381</mechanicalReduction>
</transmission>
<joint name="fl_caster_r_wheel_joint" type="continuous">
<axis xyz="0 1 0"/>
<limit effort="7" velocity="15"/>
<!-- alpha tested effort and velocity limits -->
<safety_controller k_velocity="10"/>
<dynamics damping="1.0" friction="0.0"/>
<origin rpy="0 0 0" xyz="0 -0.049 0"/>
<parent link="fl_caster_rotation_link"/>
<child link="fl_caster_r_wheel_link"/>
</joint>
<link name="fl_caster_r_wheel_link">
<inertial>
<mass value="0.44036"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983" iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/base_v0/wheel.dae"/>
</geometry>
<material name="Wheel_r"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<!-- rotation because cyl. geom primitive has symmetry axis in +x direction -->
<geometry>
<cylinder length="0.034" radius="0.074792"/>
</geometry>
</collision>
</link>
<!-- extensions -->
<gazebo reference="fl_caster_r_wheel_link">
<mu1 value="100.0"/>
<mu2 value="100.0"/>
<kp value="1000000.0"/>
<kd value="1.0"/>
<maxVel value="100.0"/>
<minDepth value="0.0"/>
</gazebo>
<transmission name="fl_caster_r_wheel_trans" type="pr2_mechanism_model/SimpleTransmission">
<actuator name="fl_caster_r_wheel_motor"/>
<joint name="fl_caster_r_wheel_joint"/>
<mechanicalReduction>-79.2380952381</mechanicalReduction>
</transmission>
<!-- extensions -->
<gazebo reference="fl_caster_rotation_link">
<material value="PR2/caster_texture"/>
</gazebo>
<joint name="fr_caster_rotation_joint" type="continuous">
<axis xyz="0 0 1"/>
<limit effort="6.5" velocity="10"/>
<!-- alpha tested velocity and effort limits -->
<safety_controller k_velocity="10"/>
<calibration rising="-0.785398163397"/>
<dynamics damping="1.0" friction="0.0"/>
<origin rpy="0 0 0" xyz="0.2246 -0.2246 0.0282"/>
<parent link="base_link"/>
<child link="fr_caster_rotation_link"/>
</joint>
<link name="fr_caster_rotation_link">
<inertial>
<mass value="3.473082"/>
<origin xyz="0 0 0.07"/>
<inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983" iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/base_v0/caster.stl"/>
</geometry>
<material name="Caster"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/base_v0/caster_L.stl"/>
</geometry>
</collision>
</link>
<!-- extensions -->
<transmission name="fr_caster_rotation_trans" type="pr2_mechanism_model/SimpleTransmission">
<actuator name="fr_caster_rotation_motor"/>
<joint name="fr_caster_rotation_joint"/>
<mechanicalReduction>-79.2380952381</mechanicalReduction>
</transmission>
<!-- wheel macros -->
<joint name="fr_caster_l_wheel_joint" type="continuous">
<axis xyz="0 1 0"/>
<limit effort="7" velocity="15"/>
<!-- alpha tested effort and velocity limits -->
<safety_controller k_velocity="10"/>
<dynamics damping="1.0" friction="0.0"/>
<origin rpy="0 0 0" xyz="0 0.049 0"/>
<parent link="fr_caster_rotation_link"/>
<child link="fr_caster_l_wheel_link"/>
</joint>
<link name="fr_caster_l_wheel_link">
<inertial>
<mass value="0.44036"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983" iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/base_v0/wheel.dae"/>
</geometry>
<material name="Wheel_l"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<!-- rotation because cyl. geom primitive has symmetry axis in +x direction -->
<geometry>
<cylinder length="0.034" radius="0.074792"/>
</geometry>
</collision>
</link>
<!-- extensions -->
<gazebo reference="fr_caster_l_wheel_link">
<mu1 value="100.0"/>
<mu2 value="100.0"/>
<kp value="1000000.0"/>
<kd value="1.0"/>
<maxVel value="100.0"/>
<minDepth value="0.0"/>
</gazebo>
<transmission name="fr_caster_l_wheel_trans" type="pr2_mechanism_model/SimpleTransmission">
<actuator name="fr_caster_l_wheel_motor"/>
<joint name="fr_caster_l_wheel_joint"/>
<mechanicalReduction>79.2380952381</mechanicalReduction>
</transmission>
<joint name="fr_caster_r_wheel_joint" type="continuous">
<axis xyz="0 1 0"/>
<limit effort="7" velocity="15"/>
<!-- alpha tested effort and velocity limits -->
<safety_controller k_velocity="10"/>
<dynamics damping="1.0" friction="0.0"/>
<origin rpy="0 0 0" xyz="0 -0.049 0"/>
<parent link="fr_caster_rotation_link"/>
<child link="fr_caster_r_wheel_link"/>
</joint>
<link name="fr_caster_r_wheel_link">
<inertial>
<mass value="0.44036"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983" iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/base_v0/wheel.dae"/>
</geometry>
<material name="Wheel_r"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<!-- rotation because cyl. geom primitive has symmetry axis in +x direction -->
<geometry>
<cylinder length="0.034" radius="0.074792"/>
</geometry>
</collision>
</link>
<!-- extensions -->
<gazebo reference="fr_caster_r_wheel_link">
<mu1 value="100.0"/>
<mu2 value="100.0"/>
<kp value="1000000.0"/>
<kd value="1.0"/>
<maxVel value="100.0"/>
<minDepth value="0.0"/>
</gazebo>
<transmission name="fr_caster_r_wheel_trans" type="pr2_mechanism_model/SimpleTransmission">
<actuator name="fr_caster_r_wheel_motor"/>
<joint name="fr_caster_r_wheel_joint"/>
<mechanicalReduction>-79.2380952381</mechanicalReduction>
</transmission>
<!-- extensions -->
<gazebo reference="fr_caster_rotation_link">
<material value="PR2/caster_texture"/>
</gazebo>
<joint name="bl_caster_rotation_joint" type="continuous">
<axis xyz="0 0 1"/>
<limit effort="6.5" velocity="10"/>
<!-- alpha tested velocity and effort limits -->
<safety_controller k_velocity="10"/>
<calibration rising="2.35619449019"/>
<dynamics damping="1.0" friction="0.0"/>
<origin rpy="0 0 0" xyz="-0.2246 0.2246 0.0282"/>
<parent link="base_link"/>
<child link="bl_caster_rotation_link"/>
</joint>
<link name="bl_caster_rotation_link">
<inertial>
<mass value="3.473082"/>
<origin xyz="0 0 0.07"/>
<inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983" iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/base_v0/caster.stl"/>
</geometry>
<material name="Caster"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/base_v0/caster_L.stl"/>
</geometry>
</collision>
</link>
<!-- extensions -->
<transmission name="bl_caster_rotation_trans" type="pr2_mechanism_model/SimpleTransmission">
<actuator name="bl_caster_rotation_motor"/>
<joint name="bl_caster_rotation_joint"/>
<mechanicalReduction>-79.2380952381</mechanicalReduction>
</transmission>
<!-- wheel macros -->
<joint name="bl_caster_l_wheel_joint" type="continuous">
<axis xyz="0 1 0"/>
<limit effort="7" velocity="15"/>
<!-- alpha tested effort and velocity limits -->
<safety_controller k_velocity="10"/>
<dynamics damping="1.0" friction="0.0"/>
<origin rpy="0 0 0" xyz="0 0.049 0"/>
<parent link="bl_caster_rotation_link"/>
<child link="bl_caster_l_wheel_link"/>
</joint>
<link name="bl_caster_l_wheel_link">
<inertial>
<mass value="0.44036"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983" iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/base_v0/wheel.dae"/>
</geometry>
<material name="Wheel_l"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<!-- rotation because cyl. geom primitive has symmetry axis in +x direction -->
<geometry>
<cylinder length="0.034" radius="0.074792"/>
</geometry>
</collision>
</link>
<!-- extensions -->
<gazebo reference="bl_caster_l_wheel_link">
<mu1 value="100.0"/>
<mu2 value="100.0"/>
<kp value="1000000.0"/>
<kd value="1.0"/>
<maxVel value="100.0"/>
<minDepth value="0.0"/>
</gazebo>
<transmission name="bl_caster_l_wheel_trans" type="pr2_mechanism_model/SimpleTransmission">
<actuator name="bl_caster_l_wheel_motor"/>
<joint name="bl_caster_l_wheel_joint"/>
<mechanicalReduction>79.2380952381</mechanicalReduction>
</transmission>
<joint name="bl_caster_r_wheel_joint" type="continuous">
<axis xyz="0 1 0"/>
<limit effort="7" velocity="15"/>
<!-- alpha tested effort and velocity limits -->
<safety_controller k_velocity="10"/>
<dynamics damping="1.0" friction="0.0"/>
<origin rpy="0 0 0" xyz="0 -0.049 0"/>
<parent link="bl_caster_rotation_link"/>
<child link="bl_caster_r_wheel_link"/>
</joint>
<link name="bl_caster_r_wheel_link">
<inertial>
<mass value="0.44036"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983" iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/base_v0/wheel.dae"/>
</geometry>
<material name="Wheel_r"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<!-- rotation because cyl. geom primitive has symmetry axis in +x direction -->
<geometry>
<cylinder length="0.034" radius="0.074792"/>
</geometry>
</collision>
</link>
<!-- extensions -->
<gazebo reference="bl_caster_r_wheel_link">
<mu1 value="100.0"/>
<mu2 value="100.0"/>
<kp value="1000000.0"/>
<kd value="1.0"/>
<maxVel value="100.0"/>
<minDepth value="0.0"/>
</gazebo>
<transmission name="bl_caster_r_wheel_trans" type="pr2_mechanism_model/SimpleTransmission">
<actuator name="bl_caster_r_wheel_motor"/>
<joint name="bl_caster_r_wheel_joint"/>
<mechanicalReduction>-79.2380952381</mechanicalReduction>
</transmission>
<!-- extensions -->
<gazebo reference="bl_caster_rotation_link">
<material value="PR2/caster_texture"/>
</gazebo>
<joint name="br_caster_rotation_joint" type="continuous">
<axis xyz="0 0 1"/>
<limit effort="6.5" velocity="10"/>
<!-- alpha tested velocity and effort limits -->
<safety_controller k_velocity="10"/>
<calibration rising="2.35619449019"/>
<dynamics damping="1.0" friction="0.0"/>
<origin rpy="0 0 0" xyz="-0.2246 -0.2246 0.0282"/>
<parent link="base_link"/>
<child link="br_caster_rotation_link"/>
</joint>
<link name="br_caster_rotation_link">
<inertial>
<mass value="3.473082"/>
<origin xyz="0 0 0.07"/>
<inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983" iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/base_v0/caster.stl"/>
</geometry>
<material name="Caster"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/base_v0/caster_L.stl"/>
</geometry>
</collision>
</link>
<!-- extensions -->
<transmission name="br_caster_rotation_trans" type="pr2_mechanism_model/SimpleTransmission">
<actuator name="br_caster_rotation_motor"/>
<joint name="br_caster_rotation_joint"/>
<mechanicalReduction>-79.2380952381</mechanicalReduction>
</transmission>
<!-- wheel macros -->
<joint name="br_caster_l_wheel_joint" type="continuous">
<axis xyz="0 1 0"/>
<limit effort="7" velocity="15"/>
<!-- alpha tested effort and velocity limits -->
<safety_controller k_velocity="10"/>
<dynamics damping="1.0" friction="0.0"/>
<origin rpy="0 0 0" xyz="0 0.049 0"/>
<parent link="br_caster_rotation_link"/>
<child link="br_caster_l_wheel_link"/>
</joint>
<link name="br_caster_l_wheel_link">
<inertial>
<mass value="0.44036"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983" iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/base_v0/wheel.dae"/>
</geometry>
<material name="Wheel_l"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<!-- rotation because cyl. geom primitive has symmetry axis in +x direction -->
<geometry>
<cylinder length="0.034" radius="0.074792"/>
</geometry>
</collision>
</link>
<!-- extensions -->
<gazebo reference="br_caster_l_wheel_link">
<mu1 value="100.0"/>
<mu2 value="100.0"/>
<kp value="1000000.0"/>
<kd value="1.0"/>
<maxVel value="100.0"/>
<minDepth value="0.0"/>
</gazebo>
<transmission name="br_caster_l_wheel_trans" type="pr2_mechanism_model/SimpleTransmission">
<actuator name="br_caster_l_wheel_motor"/>
<joint name="br_caster_l_wheel_joint"/>
<mechanicalReduction>79.2380952381</mechanicalReduction>
</transmission>
<joint name="br_caster_r_wheel_joint" type="continuous">
<axis xyz="0 1 0"/>
<limit effort="7" velocity="15"/>
<!-- alpha tested effort and velocity limits -->
<safety_controller k_velocity="10"/>
<dynamics damping="1.0" friction="0.0"/>
<origin rpy="0 0 0" xyz="0 -0.049 0"/>
<parent link="br_caster_rotation_link"/>
<child link="br_caster_r_wheel_link"/>
</joint>
<link name="br_caster_r_wheel_link">
<inertial>
<mass value="0.44036"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.012411765597" ixy="-0.000711733678" ixz="0.00050272983" iyy="0.015218160428" iyz="-0.000004273467" izz="0.011763977943"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/base_v0/wheel.dae"/>
</geometry>
<material name="Wheel_r"/>
</visual>
<collision>
<origin rpy="1.57079632679 0 0" xyz="0 0 0"/>
<!-- rotation because cyl. geom primitive has symmetry axis in +x direction -->
<geometry>
<cylinder length="0.034" radius="0.074792"/>
</geometry>
</collision>
</link>
<!-- extensions -->
<gazebo reference="br_caster_r_wheel_link">
<mu1 value="100.0"/>
<mu2 value="100.0"/>
<kp value="1000000.0"/>
<kd value="1.0"/>
<maxVel value="100.0"/>
<minDepth value="0.0"/>
</gazebo>
<transmission name="br_caster_r_wheel_trans" type="pr2_mechanism_model/SimpleTransmission">
<actuator name="br_caster_r_wheel_motor"/>
<joint name="br_caster_r_wheel_joint"/>
<mechanicalReduction>-79.2380952381</mechanicalReduction>
</transmission>
<!-- extensions -->
<gazebo reference="br_caster_rotation_link">
<material value="PR2/caster_texture"/>
</gazebo>
<!-- gazebo extensions -->
<gazebo reference="base_link">
<selfCollide>false</selfCollide>
<sensor name="base_contact_sensor" type="contact">
<always_on>true</always_on>
<update_rate>100.0</update_rate>
<contact>
<collision>base_link_collision</collision>
</contact>
<plugin filename="libgazebo_ros_bumper.so" name="base_gazebo_ros_bumper_controller">
<alwaysOn>true</alwaysOn>
<updateRate>100.0</updateRate>
<bumperTopicName>base_bumper</bumperTopicName>
<frameName>world</frameName>
</plugin>
</sensor>
</gazebo>
<gazebo reference="base_bellow_link">
<material value="PR2/Black"/>
</gazebo>
<gazebo>
<plugin filename="libgazebo_ros_p3d.so" name="p3d_base_controller">
<alwaysOn>true</alwaysOn>
<updateRate>100.0</updateRate>
<bodyName>base_link</bodyName>
<topicName>base_pose_ground_truth</topicName>
<gaussianNoise>0.01</gaussianNoise>
<frameName>map</frameName>
<xyzOffsets>0 0 0</xyzOffsets>
<rpyOffsets>0 0 0</rpyOffsets>
</plugin>
</gazebo>
<joint name="torso_lift_joint" type="prismatic">
<axis xyz="0 0 1"/>
<limit effort="10000" lower="0.0" upper="0.33" velocity="0.013"/>
<!-- alpha tested velocity and effort limits -->
<safety_controller k_position="100" k_velocity="2000000" soft_lower_limit="0.0115" soft_upper_limit="0.325"/>
<calibration falling="0.00475"/>
<dynamics damping="20000.0"/>
<origin rpy="0 0 0" xyz="-0.05 0 0.739675"/>
<parent link="base_link"/>
<child link="torso_lift_link"/>
</joint>
<link name="torso_lift_link">
<inertial>
<mass value="36.248046"/>
<origin xyz="-0.1 0 -0.0885"/>
<inertia ixx="2.771653750257" ixy="0.004284522609" ixz="-0.160418504506" iyy="2.510019507959" iyz="0.029664468704" izz="0.526432355569"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/torso_v0/torso_lift.dae"/>
</geometry>
<material name="Grey2"/>
</visual>
<collision name="torso_lift_collision">
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/torso_v0/torso_lift_L.stl"/>
</geometry>
</collision>
</link>
<joint name="l_torso_lift_side_plate_joint" type="fixed">
<origin xyz="0.0535 0.209285 0.176625"/>
<!-- location of bottom front bolt hole location -->
<parent link="torso_lift_link"/>
<child link="l_torso_lift_side_plate_link"/>
</joint>
<link name="l_torso_lift_side_plate_link">
<inertial>
<mass value="0.1"/>
<origin xyz="-0.0625 0.0 0.05"/>
<!-- center of the 12.5cm by 10cm bolt hole pattern -->
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
</inertial>
</link>
<joint name="r_torso_lift_side_plate_joint" type="fixed">
<origin xyz="0.0535 -0.209285 0.176625"/>
<!-- location of bottom front bolt hole location -->
<parent link="torso_lift_link"/>
<child link="r_torso_lift_side_plate_link"/>
</joint>
<link name="r_torso_lift_side_plate_link">
<inertial>
<mass value="0.1"/>
<origin xyz="-0.0625 0.0 0.05"/>
<!-- center of the 12.5cm by 10cm bolt hole pattern -->
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
</inertial>
</link>
<!-- actuated motor screw joint -->
<link name="torso_lift_motor_screw_link">
<inertial>
<mass value="1.0"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
</inertial>
<!-- for debugging only
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.5 0.7 0.01" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.5 0.7 0.01" />
</geometry>
</collision>
-->
</link>
<joint name="torso_lift_motor_screw_joint" type="continuous">
<origin xyz="-0.15 0.0 0.7"/>
<axis xyz="0 0 1"/>
<parent link="base_link"/>
<child link="torso_lift_motor_screw_link"/>
<dynamics damping="0.0001"/>
</joint>
<!-- extensions -->
<gazebo reference="torso_lift_link">
<sensor name="torso_lift_contact_sensor" type="contact">
<contact>
<collision>torso_lift_link_collision</collision>
</contact>
<update_rate>100.0</update_rate>
<plugin filename="libgazebo_ros_bumper.so" name="torso_lift_gazebo_ros_bumper_controller">
<alwaysOn>true</alwaysOn>
<updateRate>100.0</updateRate>