]> defiant.homedns.org Git - wt_open_manipulator.git/blob - urdf/open_manipulator.urdf.xacro
f1a5529d28f818c3077a20a4ff85f60c99dd09dc
[wt_open_manipulator.git] / urdf / open_manipulator.urdf.xacro
1 <?xml version="1.0"?>
2 <!-- Open_Manipulator Chain -->
3 <robot name="open_manipulator" xmlns:xacro="http://ros.org/wiki/xacro">
4
5         <!-- Import all Gazebo-customization elements, including Gazebo colors -->
6         <xacro:include filename="$(find open_manipulator_description)/urdf/open_manipulator.gazebo.xacro" />
7         <!-- Import Rviz colors -->
8         <xacro:include filename="$(find open_manipulator_description)/urdf/materials.xacro" />
9
10         <!-- Transmission macro -->
11         <xacro:macro name="SimpleTransmission" params="joint n">
12                 <transmission name="tran${n}">
13                         <type>transmission_interface/SimpleTransmission</type>
14                         <joint name="${joint}">
15                                 <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
16                         </joint>
17                         <actuator name="motor${n}">
18                                 <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
19                                 <mechanicalReduction>1</mechanicalReduction>
20                         </actuator>
21                 </transmission>
22         </xacro:macro>
23
24         <!-- Link 1 -->
25         <link name="link1">
26                 <visual>
27                         <origin xyz="0 0 0" rpy="0 0 0"/>
28                         <geometry>
29                                 <mesh filename="package://open_manipulator_description/meshes/chain_link1.stl" scale="0.001 0.001 0.001"/>
30                         </geometry>
31                         <material name="grey"/>
32                 </visual>
33
34                 <collision>
35                         <origin xyz="0 0 0" rpy="0 0 0"/>
36                         <geometry>
37                                 <mesh filename="package://open_manipulator_description/meshes/chain_link1.stl" scale="0.001 0.001 0.001"/>
38                         </geometry>
39                 </collision>
40
41 <!--    <inertial>
42       <origin xyz="0 0 0" />
43       <mass value="0.082" />
44       <inertia ixx="0.1" ixy="0.0" ixz="0.0"
45                iyy="0.1" iyz="0.0"
46                izz="0.1" />
47     </inertial>-->
48
49      <inertial>
50              <origin xyz="3.0876154e-04 0.0000000e+00 -1.2176461e-04" />
51              <mass value="7.9119962e-02" />
52              <inertia ixx="1.2505234e-05" ixy="0.0" ixz="-1.7855208e-07"
53                      iyy="2.1898364e-05" iyz="0.0"
54                      izz="1.9267361e-05" />
55      </inertial>
56   </link>
57
58   <!-- Joint 1 -->
59   <joint name="joint1" type="revolute">
60           <parent link="link1"/>
61           <child link="link2"/>
62           <origin xyz="0.012 0.0 0.017" rpy="0 0 0"/>
63           <axis xyz="0 0 1"/>
64           <limit velocity="4.8" effort="1" lower="${-pi}" upper="${pi}" />
65   </joint>
66
67   <!-- Transmission 1 -->
68   <xacro:SimpleTransmission n="1" joint="joint1" />
69
70   <!--  Link 2 -->
71   <link name="link2">
72           <visual>
73                   <origin xyz="0 0 0.019" rpy="0 0 0"/>
74                   <geometry>
75                           <mesh filename="package://open_manipulator_description/meshes/chain_link2.stl" scale="0.001 0.001 0.001"/>
76                   </geometry>
77                   <material name="grey"/>
78           </visual>
79
80           <collision>
81                   <origin xyz="0 0 0.019" rpy="0 0 0"/>
82                   <geometry>
83                           <mesh filename="package://open_manipulator_description/meshes/chain_link2.stl" scale="0.001 0.001 0.001"/>
84                   </geometry>
85           </collision>
86
87 <!--    <inertial>
88       <origin xyz="0 0 0" />
89       <mass value="0.098" />
90       <inertia ixx="0.1" ixy="0.0" ixz="0.0"
91                iyy="0.1" iyz="0.0"
92                izz="0.1" />
93     </inertial>-->
94
95      <inertial>
96              <origin xyz="-3.0184870e-04 5.4043684e-04 ${0.018 + 2.9433464e-02}" />
97              <mass value="9.8406837e-02" />
98              <inertia ixx="3.4543422e-05" ixy="-1.6031095e-08" ixz="-3.8375155e-07"
99                      iyy="3.2689329e-05" iyz="2.8511935e-08"
100                      izz="1.8850320e-05" />
101      </inertial>
102   </link>
103
104   <!--  Joint 2 -->
105   <joint name="joint2" type="revolute">
106           <parent link="link2"/>
107           <child link="link3"/>
108           <origin xyz="0.0 0.0 0.0595" rpy="0 0 0"/>
109           <axis xyz="0 1 0"/>
110           <limit velocity="4.8" effort="1" lower="${-pi*0.64}" upper="${pi*0.64}" />
111   </joint>
112
113   <!-- Transmission 2 -->
114   <xacro:SimpleTransmission n="2" joint="joint2" />
115
116   <!--  Link 3 -->
117   <link name="link3">
118           <visual>
119                   <origin xyz="0 0 0" rpy="0 0 0"/>
120                   <geometry>
121                           <mesh filename="package://open_manipulator_description/meshes/chain_link3.stl" scale="0.001 0.001 0.001"/>
122                   </geometry>
123                   <material name="grey"/>
124           </visual>
125
126           <collision>
127                   <origin xyz="0 0 0" rpy="0 0 0"/>
128                   <geometry>
129                           <mesh filename="package://open_manipulator_description/meshes/chain_link3.stl" scale="0.001 0.001 0.001"/>
130                   </geometry>
131           </collision>
132
133 <!--    <inertial>
134       <origin xyz="0 0 0" />
135       <mass value="0.136" />
136       <inertia ixx="0.1" ixy="0.0" ixz="0.0"
137                iyy="0.1" iyz="0.0"
138                izz="0.1" />
139     </inertial>-->
140
141      <inertial>
142              <origin xyz="1.0308393e-02 3.7743363e-04 1.0170197e-01" />
143              <mass value="1.3850917e-01" />
144              <inertia ixx="3.3055381e-04" ixy="-9.7940978e-08" ixz="-3.8505711e-05"
145                      iyy="3.4290447e-04" iyz="-1.5717516e-06"
146                      izz="6.0346498e-05" />
147      </inertial>
148   </link>
149
150   <!--  Joint 3 -->
151   <joint name="joint3" type="revolute">
152           <parent link="link3"/>
153           <child link="link4"/>
154           <origin xyz="0.024 0 0.128" rpy="0 0 0"/>
155           <axis xyz="0 1 0"/>
156           <limit velocity="4.8" effort="1" lower="${-pi*0.64}" upper="${pi*0.48}" />
157   </joint>
158
159   <!-- Transmission 3 -->
160   <xacro:SimpleTransmission n="3" joint="joint3" />
161
162   <!--  Link 4 -->
163   <link name="link4">
164           <visual>
165                   <origin xyz="0 0 0" rpy="0 0 0"/>
166                   <geometry>
167                           <mesh filename="package://open_manipulator_description/meshes/chain_link4.stl" scale="0.001 0.001 0.001"/>
168                   </geometry>
169                   <material name="grey"/>
170           </visual>
171
172           <collision>
173                   <origin xyz="0 0 0" rpy="0 0 0"/>
174                   <geometry>
175                           <mesh filename="package://open_manipulator_description/meshes/chain_link4.stl" scale="0.001 0.001 0.001"/>
176                   </geometry>
177           </collision>
178
179 <!--    <inertial>
180       <origin xyz="0 0 0" />
181       <mass value="0.131" />
182       <inertia ixx="0.1" ixy="0.0" ixz="0.0"
183                iyy="0.1" iyz="0.0"
184                izz="0.1" />
185     </inertial>-->
186
187      <inertial>
188              <origin xyz="9.0909590e-02 3.8929816e-04 2.2413279e-04" />
189              <mass value="1.3274562e-01" />
190              <inertia ixx="3.0654178e-05" ixy="-1.2764155e-06" ixz="-2.6874417e-07"
191                      iyy="2.4230292e-04" iyz="1.1559550e-08"
192                      izz="2.5155057e-04" />
193      </inertial>
194   </link>
195
196   <!--  Joint 4 -->
197   <joint name="joint4" type="revolute">
198           <parent link="link4"/>
199           <child link="link5"/>
200           <origin xyz="0.124 0.0 0.0" rpy="0 0 0"/>
201           <axis xyz="0 1 0"/>
202           <limit velocity="4.8" effort="1" lower="${-pi*0.57}" upper="${pi*0.65}" />
203   </joint>
204
205   <!-- Transmission 4 -->
206   <xacro:SimpleTransmission n="4" joint="joint4" />
207
208   <!--  Link 5 -->
209   <link name="link5">
210           <visual>
211                   <origin xyz="0 0 0" rpy="0 0 0"/>
212                   <geometry>
213                           <mesh filename="package://open_manipulator_description/meshes/chain_link5.stl" scale="0.001 0.001 0.001"/>
214                   </geometry>
215                   <material name="grey"/>
216           </visual>
217
218           <collision>
219                   <origin xyz="0 0 0" rpy="0 0 0"/>
220                   <geometry>
221                           <mesh filename="package://open_manipulator_description/meshes/chain_link5.stl" scale="0.001 0.001 0.001"/>
222                   </geometry>
223           </collision>
224
225 <!--    <inertial>
226       <origin xyz="0 0 0" />
227       <mass value="0.141" />
228       <inertia ixx="0.1" ixy="0.0" ixz="0.0"
229                iyy="0.1" iyz="0.0"
230                izz="0.1" />
231     </inertial>-->
232
233      <inertial>
234              <origin xyz="4.4206755e-02 3.6839985e-07 8.9142216e-03" />
235              <mass value="1.4327573e-01" />
236              <inertia ixx="8.0870749e-05" ixy="0.0" ixz="-1.0157896e-06"
237                      iyy="7.5980465e-05" iyz="0.0"
238                      izz="9.3127351e-05" />
239      </inertial>
240   </link>
241
242   <!--  Gripper link -->
243   <link name="gripper_link">
244           <visual>
245                   <origin xyz="0.0 0.0 0" rpy="0 0 0"/>
246                   <geometry>
247                           <mesh filename="package://open_manipulator_description/meshes/chain_link_grip_l.stl" scale="0.001 0.001 0.001"/>
248                   </geometry>
249                   <material name="grey"/>
250           </visual>
251
252           <collision>
253                   <origin xyz="0.0 0.0 0" rpy="0 0 0"/>
254                   <geometry>
255                           <mesh filename="package://open_manipulator_description/meshes/chain_link_grip_l.stl" scale="0.001 0.001 0.001"/>
256                   </geometry>
257           </collision>
258
259           <inertial>
260                   <origin xyz="0 0 0" />
261                   <mass value="0.017" />
262                   <inertia ixx="1.0e-03" ixy="0.0" ixz="0.0"
263                           iyy="1.0e-03" iyz="0.0"
264                           izz="1.0e-03" />
265           </inertial>
266
267 <!--     <inertial>
268       <origin xyz="${0.028 + 8.3720668e-03} ${0.0246 + 9.9696160e-03} -4.2836895e-07" />
269       <mass value="3.2218127e-02" />
270       <inertia ixx="9.5568826e-06" ixy="2.8424644e-06" ixz="-3.2829197e-10"
271                iyy="2.2552871e-05" iyz="-3.1463634e-10"
272                izz="1.7605306e-05" />
273     </inertial>-->
274   </link>
275
276   <!--  Gripper joint -->
277   <joint name="gripper" type="prismatic">
278           <parent link="link5"/>
279           <child link="gripper_link"/>
280           <origin xyz="0.0817 0.021 0.0" rpy="0 0 0"/>
281           <axis xyz="0 1 0"/>
282           <limit velocity="4.8" effort="1" lower="-0.010" upper="0.019" />
283   </joint>
284
285   <!-- Transmission 5 -->
286   <xacro:SimpleTransmission n="5" joint="gripper" />
287
288   <!--  Gripper link sub -->
289   <link name="gripper_link_sub">
290           <visual>
291                   <origin xyz="0.0 -0.0 0" rpy="0 0 0"/>
292                   <geometry>
293                           <mesh filename="package://open_manipulator_description/meshes/chain_link_grip_r.stl" scale="0.001 0.001 0.001"/>
294                   </geometry>
295                   <material name="grey"/>
296           </visual>
297
298           <collision>
299                   <origin xyz="0.0 -0.0 0" rpy="0 0 0"/>
300                   <geometry>
301                           <mesh filename="package://open_manipulator_description/meshes/chain_link_grip_r.stl" scale="0.001 0.001 0.001"/>
302                   </geometry>
303           </collision>
304
305           <inertial>
306                   <origin xyz="0 0 0" />
307                   <mass value="0.017" />
308                   <inertia ixx="1.0e-03" ixy="0.0" ixz="0.0"
309                           iyy="1.0e-03" iyz="0.0"
310                           izz="1.0e-03" />
311           </inertial>
312
313 <!--     <inertial>
314       <origin xyz="${0.028 + 8.3720668e-03} ${-0.0246 - 9.9696160e-03} -4.2836895e-07" />
315       <mass value="3.2218127e-02" />
316       <inertia ixx="9.5568826e-06" ixy="2.8424644e-06" ixz="-3.2829197e-10"
317                iyy="2.2552871e-05" iyz="-3.1463634e-10"
318                izz="1.7605306e-05" />
319     </inertial>-->
320   </link>
321
322   <!--  Gripper joint sub -->
323   <joint name="gripper_sub" type="prismatic">
324           <parent link="link5"/>
325           <child link="gripper_link_sub"/>
326           <origin xyz="0.0817 -0.021 0" rpy="0 0 0"/>
327           <axis xyz="0 -1 0"/>
328           <limit velocity="4.8" effort="1" lower="-0.010" upper="0.019" />
329           <mimic joint="gripper" multiplier="1"/>
330   </joint>
331
332   <!-- Transmission 6 -->
333   <xacro:SimpleTransmission n="6" joint="gripper_sub" />
334
335   <!-- end effector joint -->
336   <joint name="end_effector_joint" type="fixed">
337           <origin xyz="0.126 0.0 0.0" rpy="0 0 0"/>
338           <parent link="link5"/>
339           <child link="end_effector_link"/>
340   </joint>
341
342   <!-- end effector link -->
343   <link name="end_effector_link">
344           <visual>
345                   <origin xyz="0 0 0" rpy="0 0 0"/>
346                   <geometry>
347                           <box size="0.01 0.01 0.01" />
348                   </geometry>
349                   <material name="red"/>
350           </visual>
351
352           <inertial>
353                   <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
354                   <mass value="0.001"/>
355                   <inertia ixx="1.0e-06" ixy="0.0" ixz="0.0" iyy="1.0e-06" iyz="0.0" izz="1.0e-06" />
356           </inertial>
357   </link>
358
359 </robot>