]> defiant.homedns.org Git - wt_open_manipulator.git/blob - urdf/open_manipulator.urdf
Automatically power up/down
[wt_open_manipulator.git] / urdf / open_manipulator.urdf
1 <?xml version="1.0" encoding="utf-8"?>
2 <!-- =================================================================================== -->
3 <!-- |    This document was autogenerated by xacro from open_manipulator.urdf.xacro    | -->
4 <!-- |    EDITING THIS FILE BY HAND IS NOT RECOMMENDED                                 | -->
5 <!-- =================================================================================== -->
6 <!-- Open_Manipulator Chain -->
7 <robot name="open_manipulator" xmlns:xacro="http://ros.org/wiki/xacro">
8   <!-- World -->
9   <gazebo reference="world">
10   </gazebo>
11   <gazebo reference="link1">
12     <kp>1000000.0</kp>
13     <kd>100.0</kd>
14     <mu1>30.0</mu1>
15     <mu2>30.0</mu2>
16     <maxVel>1.0</maxVel>
17     <minDepth>0.001</minDepth>
18     <material>Gazebo/DarkGrey</material>
19   </gazebo>
20   <gazebo reference="link2">
21     <kp>1000000.0</kp>
22     <kd>100.0</kd>
23     <mu1>30.0</mu1>
24     <mu2>30.0</mu2>
25     <maxVel>1.0</maxVel>
26     <minDepth>0.001</minDepth>
27     <material>Gazebo/DarkGrey</material>
28   </gazebo>
29   <gazebo reference="link3">
30     <kp>1000000.0</kp>
31     <kd>100.0</kd>
32     <mu1>30.0</mu1>
33     <mu2>30.0</mu2>
34     <maxVel>1.0</maxVel>
35     <minDepth>0.001</minDepth>
36     <material>Gazebo/DarkGrey</material>
37   </gazebo>
38   <gazebo reference="link4">
39     <kp>1000000.0</kp>
40     <kd>100.0</kd>
41     <mu1>30.0</mu1>
42     <mu2>30.0</mu2>
43     <maxVel>1.0</maxVel>
44     <minDepth>0.001</minDepth>
45     <material>Gazebo/DarkGrey</material>
46   </gazebo>
47   <gazebo reference="link5">
48     <kp>1000000.0</kp>
49     <kd>100.0</kd>
50     <mu1>30.0</mu1>
51     <mu2>30.0</mu2>
52     <maxVel>1.0</maxVel>
53     <minDepth>0.001</minDepth>
54     <material>Gazebo/DarkGrey</material>
55   </gazebo>
56   <gazebo reference="gripper_link">
57     <kp>1000000.0</kp>
58     <kd>100.0</kd>
59     <mu1>30.0</mu1>
60     <mu2>30.0</mu2>
61     <maxVel>1.0</maxVel>
62     <minDepth>0.001</minDepth>
63     <material>Gazebo/DarkGrey</material>
64   </gazebo>
65   <gazebo reference="gripper_link_sub">
66     <kp>1000000.0</kp>
67     <kd>100.0</kd>
68     <mu1>30.0</mu1>
69     <mu2>30.0</mu2>
70     <maxVel>1.0</maxVel>
71     <minDepth>0.001</minDepth>
72     <material>Gazebo/DarkGrey</material>
73   </gazebo>
74   <!-- end effector link -->
75   <gazebo reference="end_effector_link">
76     <material>Gazebo/Red</material>
77   </gazebo>
78   <!-- ros_control plugin -->
79   <gazebo>
80     <plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
81       <robotNamespace>open_manipulator</robotNamespace>
82       <controlPeriod>0.001</controlPeriod>
83       <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
84       <legacyModeNS>true</legacyModeNS>
85     </plugin>
86   </gazebo>
87   <material name="black">
88     <color rgba="0.0 0.0 0.0 1.0"/>
89   </material>
90   <material name="white">
91     <color rgba="1.0 1.0 1.0 1.0"/>
92   </material>
93   <material name="red">
94     <color rgba="0.8 0.0 0.0 1.0"/>
95   </material>
96   <material name="blue">
97     <color rgba="0.0 0.0 0.8 1.0"/>
98   </material>
99   <material name="green">
100     <color rgba="0.0 0.8 0.0 1.0"/>
101   </material>
102   <material name="grey">
103     <color rgba="0.5 0.5 0.5 1.0"/>
104   </material>
105   <material name="orange">
106     <color rgba="1.0 0.423529411765 0.0392156862745 1.0"/>
107   </material>
108   <material name="brown">
109     <color rgba="0.870588235294 0.811764705882 0.764705882353 1.0"/>
110   </material>
111   <!-- Link 1 -->
112   <link name="link1">
113     <visual>
114       <origin rpy="0 0 0" xyz="0 0 0"/>
115       <geometry>
116         <mesh filename="package://open_manipulator_description/meshes/chain_link1.stl" scale="0.001 0.001 0.001"/>
117       </geometry>
118       <material name="grey"/>
119     </visual>
120     <collision>
121       <origin rpy="0 0 0" xyz="0 0 0"/>
122       <geometry>
123         <mesh filename="package://open_manipulator_description/meshes/chain_link1.stl" scale="0.001 0.001 0.001"/>
124       </geometry>
125     </collision>
126     <!--    <inertial>
127       <origin xyz="0 0 0" />
128       <mass value="0.082" />
129       <inertia ixx="0.1" ixy="0.0" ixz="0.0"
130                iyy="0.1" iyz="0.0"
131                izz="0.1" />
132     </inertial>-->
133     <inertial>
134       <origin xyz="3.0876154e-04 0.0000000e+00 -1.2176461e-04"/>
135       <mass value="7.9119962e-02"/>
136       <inertia ixx="1.2505234e-05" ixy="0.0" ixz="-1.7855208e-07" iyy="2.1898364e-05" iyz="0.0" izz="1.9267361e-05"/>
137     </inertial>
138   </link>
139   <!-- Joint 1 -->
140   <joint name="joint1" type="revolute">
141     <parent link="link1"/>
142     <child link="link2"/>
143     <origin rpy="0 0 0" xyz="0.012 0.0 0.017"/>
144     <axis xyz="0 0 1"/>
145     <limit effort="1" lower="-3.14159265359" upper="3.14159265359" velocity="4.8"/>
146   </joint>
147   <transmission name="tran1">
148     <type>transmission_interface/SimpleTransmission</type>
149     <joint name="joint1">
150       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
151     </joint>
152     <actuator name="motor1">
153       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
154       <mechanicalReduction>1</mechanicalReduction>
155     </actuator>
156   </transmission>
157   <!--  Link 2 -->
158   <link name="link2">
159     <visual>
160       <origin rpy="0 0 0" xyz="0 0 0.019"/>
161       <geometry>
162         <mesh filename="package://open_manipulator_description/meshes/chain_link2.stl" scale="0.001 0.001 0.001"/>
163       </geometry>
164       <material name="grey"/>
165     </visual>
166     <collision>
167       <origin rpy="0 0 0" xyz="0 0 0.019"/>
168       <geometry>
169         <mesh filename="package://open_manipulator_description/meshes/chain_link2.stl" scale="0.001 0.001 0.001"/>
170       </geometry>
171     </collision>
172     <!--    <inertial>
173       <origin xyz="0 0 0" />
174       <mass value="0.098" />
175       <inertia ixx="0.1" ixy="0.0" ixz="0.0"
176                iyy="0.1" iyz="0.0"
177                izz="0.1" />
178     </inertial>-->
179     <inertial>
180       <origin xyz="-3.0184870e-04 5.4043684e-04 0.047433464"/>
181       <mass value="9.8406837e-02"/>
182       <inertia ixx="3.4543422e-05" ixy="-1.6031095e-08" ixz="-3.8375155e-07" iyy="3.2689329e-05" iyz="2.8511935e-08" izz="1.8850320e-05"/>
183     </inertial>
184   </link>
185   <!--  Joint 2 -->
186   <joint name="joint2" type="revolute">
187     <parent link="link2"/>
188     <child link="link3"/>
189     <origin rpy="0 0 0" xyz="0.0 0.0 0.0595"/>
190     <axis xyz="0 1 0"/>
191     <limit effort="1" lower="-2.0106192983" upper="2.0106192983" velocity="4.8"/>
192   </joint>
193   <transmission name="tran2">
194     <type>transmission_interface/SimpleTransmission</type>
195     <joint name="joint2">
196       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
197     </joint>
198     <actuator name="motor2">
199       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
200       <mechanicalReduction>1</mechanicalReduction>
201     </actuator>
202   </transmission>
203   <!--  Link 3 -->
204   <link name="link3">
205     <visual>
206       <origin rpy="0 0 0" xyz="0 0 0"/>
207       <geometry>
208         <mesh filename="package://open_manipulator_description/meshes/chain_link3.stl" scale="0.001 0.001 0.001"/>
209       </geometry>
210       <material name="grey"/>
211     </visual>
212     <collision>
213       <origin rpy="0 0 0" xyz="0 0 0"/>
214       <geometry>
215         <mesh filename="package://open_manipulator_description/meshes/chain_link3.stl" scale="0.001 0.001 0.001"/>
216       </geometry>
217     </collision>
218     <!--    <inertial>
219       <origin xyz="0 0 0" />
220       <mass value="0.136" />
221       <inertia ixx="0.1" ixy="0.0" ixz="0.0"
222                iyy="0.1" iyz="0.0"
223                izz="0.1" />
224     </inertial>-->
225     <inertial>
226       <origin xyz="1.0308393e-02 3.7743363e-04 1.0170197e-01"/>
227       <mass value="1.3850917e-01"/>
228       <inertia ixx="3.3055381e-04" ixy="-9.7940978e-08" ixz="-3.8505711e-05" iyy="3.4290447e-04" iyz="-1.5717516e-06" izz="6.0346498e-05"/>
229     </inertial>
230   </link>
231   <!--  Joint 3 -->
232   <joint name="joint3" type="revolute">
233     <parent link="link3"/>
234     <child link="link4"/>
235     <origin rpy="0 0 0" xyz="0.024 0 0.128"/>
236     <axis xyz="0 1 0"/>
237     <limit effort="1" lower="-2.0106192983" upper="1.50796447372" velocity="4.8"/>
238   </joint>
239   <transmission name="tran3">
240     <type>transmission_interface/SimpleTransmission</type>
241     <joint name="joint3">
242       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
243     </joint>
244     <actuator name="motor3">
245       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
246       <mechanicalReduction>1</mechanicalReduction>
247     </actuator>
248   </transmission>
249   <!--  Link 4 -->
250   <link name="link4">
251     <visual>
252       <origin rpy="0 0 0" xyz="0 0 0"/>
253       <geometry>
254         <mesh filename="package://open_manipulator_description/meshes/chain_link4.stl" scale="0.001 0.001 0.001"/>
255       </geometry>
256       <material name="grey"/>
257     </visual>
258     <collision>
259       <origin rpy="0 0 0" xyz="0 0 0"/>
260       <geometry>
261         <mesh filename="package://open_manipulator_description/meshes/chain_link4.stl" scale="0.001 0.001 0.001"/>
262       </geometry>
263     </collision>
264     <!--    <inertial>
265       <origin xyz="0 0 0" />
266       <mass value="0.131" />
267       <inertia ixx="0.1" ixy="0.0" ixz="0.0"
268                iyy="0.1" iyz="0.0"
269                izz="0.1" />
270     </inertial>-->
271     <inertial>
272       <origin xyz="9.0909590e-02 3.8929816e-04 2.2413279e-04"/>
273       <mass value="1.3274562e-01"/>
274       <inertia ixx="3.0654178e-05" ixy="-1.2764155e-06" ixz="-2.6874417e-07" iyy="2.4230292e-04" iyz="1.1559550e-08" izz="2.5155057e-04"/>
275     </inertial>
276   </link>
277   <!--  Joint 4 -->
278   <joint name="joint4" type="revolute">
279     <parent link="link4"/>
280     <child link="link5"/>
281     <origin rpy="0 0 0" xyz="0.124 0.0 0.0"/>
282     <axis xyz="0 1 0"/>
283     <limit effort="1" lower="-1.79070781255" upper="2.04203522483" velocity="4.8"/>
284   </joint>
285   <transmission name="tran4">
286     <type>transmission_interface/SimpleTransmission</type>
287     <joint name="joint4">
288       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
289     </joint>
290     <actuator name="motor4">
291       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
292       <mechanicalReduction>1</mechanicalReduction>
293     </actuator>
294   </transmission>
295   <!--  Link 5 -->
296   <link name="link5">
297     <visual>
298       <origin rpy="0 0 0" xyz="0 0 0"/>
299       <geometry>
300         <mesh filename="package://open_manipulator_description/meshes/chain_link5.stl" scale="0.001 0.001 0.001"/>
301       </geometry>
302       <material name="grey"/>
303     </visual>
304     <collision>
305       <origin rpy="0 0 0" xyz="0 0 0"/>
306       <geometry>
307         <mesh filename="package://open_manipulator_description/meshes/chain_link5.stl" scale="0.001 0.001 0.001"/>
308       </geometry>
309     </collision>
310     <!--    <inertial>
311       <origin xyz="0 0 0" />
312       <mass value="0.141" />
313       <inertia ixx="0.1" ixy="0.0" ixz="0.0"
314                iyy="0.1" iyz="0.0"
315                izz="0.1" />
316     </inertial>-->
317     <inertial>
318       <origin xyz="4.4206755e-02 3.6839985e-07 8.9142216e-03"/>
319       <mass value="1.4327573e-01"/>
320       <inertia ixx="8.0870749e-05" ixy="0.0" ixz="-1.0157896e-06" iyy="7.5980465e-05" iyz="0.0" izz="9.3127351e-05"/>
321     </inertial>
322   </link>
323   <!--  Gripper link -->
324   <link name="gripper_link">
325     <visual>
326       <origin rpy="0 0 0" xyz="0.0 0.0 0"/>
327       <geometry>
328         <mesh filename="package://open_manipulator_description/meshes/chain_link_grip_l.stl" scale="0.001 0.001 0.001"/>
329       </geometry>
330       <material name="grey"/>
331     </visual>
332     <collision>
333       <origin rpy="0 0 0" xyz="0.0 0.0 0"/>
334       <geometry>
335         <mesh filename="package://open_manipulator_description/meshes/chain_link_grip_l.stl" scale="0.001 0.001 0.001"/>
336       </geometry>
337     </collision>
338     <inertial>
339       <origin xyz="0 0 0"/>
340       <mass value="0.017"/>
341       <inertia ixx="1.0e-03" ixy="0.0" ixz="0.0" iyy="1.0e-03" iyz="0.0" izz="1.0e-03"/>
342     </inertial>
343     <!--     <inertial>
344       <origin xyz="${0.028 + 8.3720668e-03} ${0.0246 + 9.9696160e-03} -4.2836895e-07" />
345       <mass value="3.2218127e-02" />
346       <inertia ixx="9.5568826e-06" ixy="2.8424644e-06" ixz="-3.2829197e-10"
347                iyy="2.2552871e-05" iyz="-3.1463634e-10"
348                izz="1.7605306e-05" />
349     </inertial>-->
350   </link>
351   <!--  Gripper joint -->
352   <joint name="gripper" type="prismatic">
353     <parent link="link5"/>
354     <child link="gripper_link"/>
355     <origin rpy="0 0 0" xyz="0.0817 0.021 0.0"/>
356     <axis xyz="0 1 0"/>
357     <limit effort="1" lower="-0.010" upper="0.019" velocity="4.8"/>
358   </joint>
359   <transmission name="tran5">
360     <type>transmission_interface/SimpleTransmission</type>
361     <joint name="gripper">
362       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
363     </joint>
364     <actuator name="motor5">
365       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
366       <mechanicalReduction>1</mechanicalReduction>
367     </actuator>
368   </transmission>
369   <!--  Gripper link sub -->
370   <link name="gripper_link_sub">
371     <visual>
372       <origin rpy="0 0 0" xyz="0.0 -0.0 0"/>
373       <geometry>
374         <mesh filename="package://open_manipulator_description/meshes/chain_link_grip_r.stl" scale="0.001 0.001 0.001"/>
375       </geometry>
376       <material name="grey"/>
377     </visual>
378     <collision>
379       <origin rpy="0 0 0" xyz="0.0 -0.0 0"/>
380       <geometry>
381         <mesh filename="package://open_manipulator_description/meshes/chain_link_grip_r.stl" scale="0.001 0.001 0.001"/>
382       </geometry>
383     </collision>
384     <inertial>
385       <origin xyz="0 0 0"/>
386       <mass value="0.017"/>
387       <inertia ixx="1.0e-03" ixy="0.0" ixz="0.0" iyy="1.0e-03" iyz="0.0" izz="1.0e-03"/>
388     </inertial>
389     <!--     <inertial>
390       <origin xyz="${0.028 + 8.3720668e-03} ${-0.0246 - 9.9696160e-03} -4.2836895e-07" />
391       <mass value="3.2218127e-02" />
392       <inertia ixx="9.5568826e-06" ixy="2.8424644e-06" ixz="-3.2829197e-10"
393                iyy="2.2552871e-05" iyz="-3.1463634e-10"
394                izz="1.7605306e-05" />
395     </inertial>-->
396   </link>
397   <!--  Gripper joint sub -->
398   <joint name="gripper_sub" type="prismatic">
399     <parent link="link5"/>
400     <child link="gripper_link_sub"/>
401     <origin rpy="0 0 0" xyz="0.0817 -0.021 0"/>
402     <axis xyz="0 -1 0"/>
403     <limit effort="1" lower="-0.010" upper="0.019" velocity="4.8"/>
404     <mimic joint="gripper" multiplier="1"/>
405   </joint>
406   <transmission name="tran6">
407     <type>transmission_interface/SimpleTransmission</type>
408     <joint name="gripper_sub">
409       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
410     </joint>
411     <actuator name="motor6">
412       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
413       <mechanicalReduction>1</mechanicalReduction>
414     </actuator>
415   </transmission>
416   <!-- end effector joint -->
417   <joint name="end_effector_joint" type="fixed">
418     <origin rpy="0 0 0" xyz="0.126 0.0 0.0"/>
419     <parent link="link5"/>
420     <child link="end_effector_link"/>
421   </joint>
422   <!-- end effector link -->
423   <link name="end_effector_link">
424     <visual>
425       <origin rpy="0 0 0" xyz="0 0 0"/>
426       <geometry>
427         <box size="0.01 0.01 0.01"/>
428       </geometry>
429       <material name="red"/>
430     </visual>
431     <inertial>
432       <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
433       <mass value="0.001"/>
434       <inertia ixx="1.0e-06" ixy="0.0" ixz="0.0" iyy="1.0e-06" iyz="0.0" izz="1.0e-06"/>
435     </inertial>
436   </link>
437 </robot>