]> defiant.homedns.org Git - wt_open_manipulator.git/blob - urdf/open_manipulator.urdf.xacro
replace id 12 with xm540-w270
[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.036" rpy="0 0 0"/> <!-- Height servo+horn -->
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                   <geometry>
84                           <mesh filename="package://open_manipulator_description/meshes/chain_link2.stl" scale="${0.001*33.5/28.5} ${0.001*44/34} ${0.001*58.5/46.5}"/> <!-- scale by XM540 -->
85                   </geometry>
86                   <material name="grey"/>
87           </visual>
88
89           <collision>
90                   <geometry>
91                           <mesh filename="package://open_manipulator_description/meshes/chain_link2.stl" scale="${0.001*33.5/28.5} ${0.001*44/34} ${0.001*58.5/46.5}"/> <!-- scale by XM540 -->
92                   </geometry>
93           </collision>
94
95 <!--    <inertial>
96       <origin xyz="0 0 0" />
97       <mass value="0.098" />
98       <inertia ixx="0.1" ixy="0.0" ixz="0.0"
99                iyy="0.1" iyz="0.0"
100                izz="0.1" />
101     </inertial>-->
102
103      <inertial>
104              <origin xyz="-3.0184870e-04 5.4043684e-04 ${0.018 + 2.9433464e-02}" />
105              <mass value="9.8406837e-02" />
106              <inertia ixx="3.4543422e-05" ixy="-1.6031095e-08" ixz="-3.8375155e-07"
107                      iyy="3.2689329e-05" iyz="2.8511935e-08"
108                      izz="1.8850320e-05" />
109      </inertial>
110   </link>
111
112   <!--  Joint 2 -->
113   <joint name="joint2" type="revolute">
114           <parent link="link2"/>
115           <child link="link3"/>
116           <origin xyz="0.0 0.0 0.0515" rpy="0 0 0"/> <!-- fr13-s102k to middle of servo horn -->
117           <axis xyz="0 1 0"/>
118           <limit velocity="4.8" effort="1" lower="${-pi*0.64}" upper="${pi*0.64}" />
119   </joint>
120
121   <!-- Transmission 2 -->
122   <xacro:SimpleTransmission n="2" joint="joint2" />
123
124   <!--  Link 3 -->
125   <link name="link3">
126           <visual>
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*(1+0.004/0.128)}"/> <!-- scale by 4mm more, see joint3 -->
130                   </geometry>
131                   <material name="grey"/>
132           </visual>
133
134           <collision>
135                   <origin xyz="0 0 0" rpy="0 0 0"/>
136                   <geometry>
137                           <mesh filename="package://open_manipulator_description/meshes/chain_link3.stl" scale="0.001 0.001 ${0.001*(1+0.004/0.128)}"/> <!-- scale by 4mm more, see joint3 -->
138                   </geometry>
139           </collision>
140
141 <!--    <inertial>
142       <origin xyz="0 0 0" />
143       <mass value="0.136" />
144       <inertia ixx="0.1" ixy="0.0" ixz="0.0"
145                iyy="0.1" iyz="0.0"
146                izz="0.1" />
147     </inertial>-->
148
149      <inertial>
150              <origin xyz="1.0308393e-02 3.7743363e-04 1.0170197e-01" />
151              <mass value="1.3850917e-01" />
152              <inertia ixx="3.3055381e-04" ixy="-9.7940978e-08" ixz="-3.8505711e-05"
153                      iyy="3.4290447e-04" iyz="-1.5717516e-06"
154                      izz="6.0346498e-05" />
155      </inertial>
156   </link>
157
158   <!--  Joint 3 -->
159   <joint name="joint3" type="revolute">
160           <parent link="link3"/>
161           <child link="link4"/>
162           <origin xyz="0.024 0 ${0.128+0.004}" rpy="0 0 0"/> <!-- 4mm more for FR13-H101K-->
163           <axis xyz="0 1 0"/>
164           <limit velocity="4.8" effort="1" lower="${-pi*0.64}" upper="${pi*0.48}" />
165   </joint>
166
167   <!-- Transmission 3 -->
168   <xacro:SimpleTransmission n="3" joint="joint3" />
169
170   <!--  Link 4 -->
171   <link name="link4">
172           <visual>
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                   <material name="grey"/>
178           </visual>
179
180           <collision>
181                   <origin xyz="0 0 0" rpy="0 0 0"/>
182                   <geometry>
183                           <mesh filename="package://open_manipulator_description/meshes/chain_link4.stl" scale="0.001 0.001 0.001"/>
184                   </geometry>
185           </collision>
186
187 <!--    <inertial>
188       <origin xyz="0 0 0" />
189       <mass value="0.131" />
190       <inertia ixx="0.1" ixy="0.0" ixz="0.0"
191                iyy="0.1" iyz="0.0"
192                izz="0.1" />
193     </inertial>-->
194
195      <inertial>
196              <origin xyz="9.0909590e-02 3.8929816e-04 2.2413279e-04" />
197              <mass value="1.3274562e-01" />
198              <inertia ixx="3.0654178e-05" ixy="-1.2764155e-06" ixz="-2.6874417e-07"
199                      iyy="2.4230292e-04" iyz="1.1559550e-08"
200                      izz="2.5155057e-04" />
201      </inertial>
202   </link>
203
204   <!--  Joint 4 -->
205   <joint name="joint4" type="revolute">
206           <parent link="link4"/>
207           <child link="link5"/>
208           <origin xyz="0.124 0.0 0.0" rpy="0 0 0"/>
209           <axis xyz="0 1 0"/>
210           <limit velocity="4.8" effort="1" lower="${-pi*0.57}" upper="${pi*0.65}" />
211   </joint>
212
213   <!-- Transmission 4 -->
214   <xacro:SimpleTransmission n="4" joint="joint4" />
215
216   <!--  Link 5 -->
217   <link name="link5">
218           <visual>
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                   <material name="grey"/>
224           </visual>
225
226           <collision>
227                   <origin xyz="0 0 0" rpy="0 0 0"/>
228                   <geometry>
229                           <mesh filename="package://open_manipulator_description/meshes/chain_link5.stl" scale="0.001 0.001 0.001"/>
230                   </geometry>
231           </collision>
232
233 <!--    <inertial>
234       <origin xyz="0 0 0" />
235       <mass value="0.141" />
236       <inertia ixx="0.1" ixy="0.0" ixz="0.0"
237                iyy="0.1" iyz="0.0"
238                izz="0.1" />
239     </inertial>-->
240
241      <inertial>
242              <origin xyz="4.4206755e-02 3.6839985e-07 8.9142216e-03" />
243              <mass value="1.4327573e-01" />
244              <inertia ixx="8.0870749e-05" ixy="0.0" ixz="-1.0157896e-06"
245                      iyy="7.5980465e-05" iyz="0.0"
246                      izz="9.3127351e-05" />
247      </inertial>
248   </link>
249
250   <!--  Gripper link -->
251   <link name="gripper_link">
252           <visual>
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                   <material name="grey"/>
258           </visual>
259
260           <collision>
261                   <origin xyz="0.0 0.0 0" rpy="0 0 0"/>
262                   <geometry>
263                           <mesh filename="package://open_manipulator_description/meshes/chain_link_grip_l.stl" scale="0.001 0.001 0.001"/>
264                   </geometry>
265           </collision>
266
267           <inertial>
268                   <origin xyz="0 0 0" />
269                   <mass value="0.017" />
270                   <inertia ixx="1.0e-03" ixy="0.0" ixz="0.0"
271                           iyy="1.0e-03" iyz="0.0"
272                           izz="1.0e-03" />
273           </inertial>
274
275 <!--     <inertial>
276       <origin xyz="${0.028 + 8.3720668e-03} ${0.0246 + 9.9696160e-03} -4.2836895e-07" />
277       <mass value="3.2218127e-02" />
278       <inertia ixx="9.5568826e-06" ixy="2.8424644e-06" ixz="-3.2829197e-10"
279                iyy="2.2552871e-05" iyz="-3.1463634e-10"
280                izz="1.7605306e-05" />
281     </inertial>-->
282   </link>
283
284   <!--  Gripper joint -->
285   <joint name="gripper" type="prismatic">
286           <parent link="link5"/>
287           <child link="gripper_link"/>
288           <origin xyz="0.0817 0.021 0.0" rpy="0 0 0"/>
289           <axis xyz="0 1 0"/>
290           <limit velocity="4.8" effort="1" lower="-0.010" upper="0.019" />
291   </joint>
292
293   <!-- Transmission 5 -->
294   <xacro:SimpleTransmission n="5" joint="gripper" />
295
296   <!--  Gripper link sub -->
297   <link name="gripper_link_sub">
298           <visual>
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                   <material name="grey"/>
304           </visual>
305
306           <collision>
307                   <origin xyz="0.0 -0.0 0" rpy="0 0 0"/>
308                   <geometry>
309                           <mesh filename="package://open_manipulator_description/meshes/chain_link_grip_r.stl" scale="0.001 0.001 0.001"/>
310                   </geometry>
311           </collision>
312
313           <inertial>
314                   <origin xyz="0 0 0" />
315                   <mass value="0.017" />
316                   <inertia ixx="1.0e-03" ixy="0.0" ixz="0.0"
317                           iyy="1.0e-03" iyz="0.0"
318                           izz="1.0e-03" />
319           </inertial>
320
321 <!--     <inertial>
322       <origin xyz="${0.028 + 8.3720668e-03} ${-0.0246 - 9.9696160e-03} -4.2836895e-07" />
323       <mass value="3.2218127e-02" />
324       <inertia ixx="9.5568826e-06" ixy="2.8424644e-06" ixz="-3.2829197e-10"
325                iyy="2.2552871e-05" iyz="-3.1463634e-10"
326                izz="1.7605306e-05" />
327     </inertial>-->
328   </link>
329
330   <!--  Gripper joint sub -->
331   <joint name="gripper_sub" type="prismatic">
332           <parent link="link5"/>
333           <child link="gripper_link_sub"/>
334           <origin xyz="0.0817 -0.021 0" rpy="0 0 0"/>
335           <axis xyz="0 -1 0"/>
336           <limit velocity="4.8" effort="1" lower="-0.010" upper="0.019" />
337           <mimic joint="gripper" multiplier="1"/>
338   </joint>
339
340   <!-- Transmission 6 -->
341   <xacro:SimpleTransmission n="6" joint="gripper_sub" />
342
343   <!-- end effector joint -->
344   <joint name="end_effector_joint" type="fixed">
345           <origin xyz="0.126 0.0 0.0" rpy="0 0 0"/>
346           <parent link="link5"/>
347           <child link="end_effector_link"/>
348   </joint>
349
350   <!-- end effector link -->
351   <link name="end_effector_link">
352           <visual>
353                   <origin xyz="0 0 0" rpy="0 0 0"/>
354                   <geometry>
355                           <box size="0.01 0.01 0.01" />
356                   </geometry>
357                   <material name="red"/>
358           </visual>
359
360           <inertial>
361                   <origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
362                   <mass value="0.001"/>
363                   <inertia ixx="1.0e-06" ixy="0.0" ixz="0.0" iyy="1.0e-06" iyz="0.0" izz="1.0e-06" />
364           </inertial>
365   </link>
366
367         <sensor_d435 parent="gripper_link">
368                 <origin xyz="-0.02 -0.018 0.055" rpy="0 0 0"/>
369         </sensor_d435>
370 </robot>