2 <robot name="wild_thumper">
3 <link name="base_link">
9 <box size="0.06 0.03 0.135"/>
11 <origin xyz="0 0 0.0675"/>
12 <material name="grey">
13 <color rgba="0.5 0.5 0.5 1"/>
21 <box size="0.240 0.06 0.03"/>
23 <origin xyz="0.120 0 0.0" rpy="0 0 0"/>
24 <material name="grey">
25 <color rgba="0.5 0.5 0.5 1"/>
33 <box size="0.06 0.135 0.03"/>
35 <origin xyz="0.0 0.0675 0.0" rpy="0 0 0"/>
36 <material name="grey">
37 <color rgba="0.5 0.5 0.5 1"/>
42 <link name="gripper_pole1">
45 <cylinder radius="0.04" length="0.055"/>
47 <origin xyz="0.0275 0 0" rpy="0 1.57075 0"/>
48 <material name="black">
49 <color rgba="0 0 0 1"/>
54 <link name="gripper_pole2">
57 <cylinder radius="0.0" length="0.0"/>
59 <origin xyz="0.0 0 0" rpy="0 0 0"/>
63 <link name="left_gripper">
65 <origin rpy="0.0 0 0" xyz="0 0 0"/>
67 <mesh filename="package://pr2_description/meshes/gripper_v0/l_finger.dae"/>
72 <link name="right_gripper">
74 <origin rpy="-3.1415 0 0" xyz="0 0 0"/>
76 <mesh filename="package://pr2_description/meshes/gripper_v0/l_finger.dae"/>
81 <joint name="base_to_link1" type="continuous">
82 <parent link="base_link"/>
85 <limit effort="1000.0" lower="0.0" upper="5.672320068981571" velocity="1.0"/>
88 <joint name="link_1_2_joint" type="continuous">
89 <parent link="link1"/>
92 <origin xyz="0.0 0.0 0.135" rpy="1.57075 0 0"/>
93 <limit effort="1000.0" lower="0.15045941827537324" upper="3.6110260386089577" velocity="1.0"/>
96 <joint name="link_2_3_joint" type="continuous">
97 <parent link="link2"/>
100 <origin xyz="0.240 0.0 0.0" rpy="0 0 0"/>
101 <limit effort="1000.0" lower="0.0" upper="3.141592653589793" velocity="1.0"/>
104 <joint name="gripper_joint_1" type="continuous">
105 <parent link="link3"/>
106 <child link="gripper_pole1"/>
108 <origin xyz="0 0.135 0.0" rpy="1.57075 0 1.57075"/>
109 <limit effort="1000.0" lower="-0.6981317007977319" upper="7.679448708775051" velocity="1.0"/>
112 <joint name="gripper_joint_2" type="continuous">
113 <parent link="gripper_pole1"/>
114 <child link="gripper_pole2"/>
116 <origin xyz="0.055 0.0 0.0" rpy="0 0 0"/>
117 <limit effort="1000.0" lower="-1.5707963267948966" upper="1.5707963267948966" velocity="1.0"/>
120 <joint name="right_gripper_joint" type="revolute">
121 <parent link="gripper_pole2"/>
122 <child link="right_gripper"/>
124 <origin xyz="0 -0.01 0" rpy="0 0 0"/>
125 <limit effort="1000.0" lower="0.0" upper="0.548" velocity="1.0"/>
128 <joint name="left_gripper_joint" type="revolute">
129 <parent link="gripper_pole2"/>
130 <child link="left_gripper"/>
132 <origin xyz="0 0.01 0" rpy="0 0 0" />
133 <limit effort="1000.0" lower="0.0" upper="0.548" velocity="1.0"/>