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