]> defiant.homedns.org Git - wt_open_manipulator.git/blob - urdf/open_manipulator.urdf
replace id 12 with xm540-w270
[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 /home/erik/Projects/ros_catkin_ws/src/wt_open_manipulator/urdf/open_manipulator.urdf.xacro | -->
4 <!-- |    EDITING THIS FILE BY HAND IS NOT RECOMMENDED                                 | -->
5 <!-- =================================================================================== -->
6 <!-- Open_Manipulator Chain -->
7 <robot name="open_manipulator">
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 name="open_manipulator_base">
112         </link>
113   <joint name="world_fixed" type="fixed">
114     <origin rpy="0 0 0" xyz="0 0 0"/>
115     <parent link="open_manipulator_base"/>
116     <child link="link1"/>
117   </joint>
118   <!-- Link 1 -->
119   <link name="link1">
120     <visual>
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       <material name="grey"/>
126     </visual>
127     <collision>
128       <origin rpy="0 0 0" xyz="0 0 0"/>
129       <geometry>
130         <mesh filename="package://open_manipulator_description/meshes/chain_link1.stl" scale="0.001 0.001 0.001"/>
131       </geometry>
132     </collision>
133     <!--    <inertial>
134       <origin xyz="0 0 0" />
135       <mass value="0.082" />
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     <inertial>
141       <origin xyz="3.0876154e-04 0.0000000e+00 -1.2176461e-04"/>
142       <mass value="7.9119962e-02"/>
143       <inertia ixx="1.2505234e-05" ixy="0.0" ixz="-1.7855208e-07" iyy="2.1898364e-05" iyz="0.0" izz="1.9267361e-05"/>
144     </inertial>
145   </link>
146   <!-- Joint 1 -->
147   <joint name="joint1" type="revolute">
148     <parent link="link1"/>
149     <child link="link2"/>
150     <origin rpy="0 0 0" xyz="0.012 0.0 0.036"/>
151     <!-- Height servo+horn -->
152     <axis xyz="0 0 1"/>
153     <limit effort="1" lower="-3.14159265359" upper="3.14159265359" velocity="3.1"/>
154   </joint>
155   <transmission name="tran1">
156     <type>transmission_interface/SimpleTransmission</type>
157     <joint name="joint1">
158       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
159     </joint>
160     <actuator name="motor1">
161       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
162       <mechanicalReduction>1</mechanicalReduction>
163     </actuator>
164   </transmission>
165   <!--  Link 2 -->
166   <link name="link2">
167     <visual>
168       <geometry>
169         <mesh filename="package://open_manipulator_description/meshes/chain_link2.stl" scale="0.00117543859649 0.00129411764706 0.00125806451613"/>
170         <!-- scale by XM540 -->
171       </geometry>
172       <material name="grey"/>
173     </visual>
174     <collision>
175       <geometry>
176         <mesh filename="package://open_manipulator_description/meshes/chain_link2.stl" scale="0.00117543859649 0.00129411764706 0.00125806451613"/>
177         <!-- scale by XM540 -->
178       </geometry>
179     </collision>
180     <!--    <inertial>
181       <origin xyz="0 0 0" />
182       <mass value="0.098" />
183       <inertia ixx="0.1" ixy="0.0" ixz="0.0"
184                iyy="0.1" iyz="0.0"
185                izz="0.1" />
186     </inertial>-->
187     <inertial>
188       <origin xyz="-3.0184870e-04 5.4043684e-04 0.047433464"/>
189       <mass value="9.8406837e-02"/>
190       <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"/>
191     </inertial>
192   </link>
193   <!--  Joint 2 -->
194   <joint name="joint2" type="revolute">
195     <parent link="link2"/>
196     <child link="link3"/>
197     <origin rpy="0 0 0" xyz="0.0 0.0 0.0515"/>
198     <!-- fr13-s102k to middle of servo horn -->
199     <axis xyz="0 1 0"/>
200     <limit effort="1" lower="-2.0106192983" upper="2.0106192983" velocity="4.8"/>
201   </joint>
202   <transmission name="tran2">
203     <type>transmission_interface/SimpleTransmission</type>
204     <joint name="joint2">
205       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
206     </joint>
207     <actuator name="motor2">
208       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
209       <mechanicalReduction>1</mechanicalReduction>
210     </actuator>
211   </transmission>
212   <!--  Link 3 -->
213   <link name="link3">
214     <visual>
215       <origin rpy="0 0 0" xyz="0 0 0"/>
216       <geometry>
217         <mesh filename="package://open_manipulator_description/meshes/chain_link3.stl" scale="0.001 0.001 0.00103125"/>
218         <!-- scale by 4mm more, see joint3 -->
219       </geometry>
220       <material name="grey"/>
221     </visual>
222     <collision>
223       <origin rpy="0 0 0" xyz="0 0 0"/>
224       <geometry>
225         <mesh filename="package://open_manipulator_description/meshes/chain_link3.stl" scale="0.001 0.001 0.00103125"/>
226         <!-- scale by 4mm more, see joint3 -->
227       </geometry>
228     </collision>
229     <!--    <inertial>
230       <origin xyz="0 0 0" />
231       <mass value="0.136" />
232       <inertia ixx="0.1" ixy="0.0" ixz="0.0"
233                iyy="0.1" iyz="0.0"
234                izz="0.1" />
235     </inertial>-->
236     <inertial>
237       <origin xyz="1.0308393e-02 3.7743363e-04 1.0170197e-01"/>
238       <mass value="1.3850917e-01"/>
239       <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"/>
240     </inertial>
241   </link>
242   <!--  Joint 3 -->
243   <joint name="joint3" type="revolute">
244     <parent link="link3"/>
245     <child link="link4"/>
246     <origin rpy="0 0 0" xyz="0.024 0 0.132"/>
247     <!-- 4mm more for FR13-H101K-->
248     <axis xyz="0 1 0"/>
249     <limit effort="1" lower="-2.0106192983" upper="1.50796447372" velocity="4.8"/>
250   </joint>
251   <transmission name="tran3">
252     <type>transmission_interface/SimpleTransmission</type>
253     <joint name="joint3">
254       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
255     </joint>
256     <actuator name="motor3">
257       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
258       <mechanicalReduction>1</mechanicalReduction>
259     </actuator>
260   </transmission>
261   <!--  Link 4 -->
262   <link name="link4">
263     <visual>
264       <origin rpy="0 0 0" xyz="0 0 0"/>
265       <geometry>
266         <mesh filename="package://open_manipulator_description/meshes/chain_link4.stl" scale="0.001 0.001 0.001"/>
267       </geometry>
268       <material name="grey"/>
269     </visual>
270     <collision>
271       <origin rpy="0 0 0" xyz="0 0 0"/>
272       <geometry>
273         <mesh filename="package://open_manipulator_description/meshes/chain_link4.stl" scale="0.001 0.001 0.001"/>
274       </geometry>
275     </collision>
276     <!--    <inertial>
277       <origin xyz="0 0 0" />
278       <mass value="0.131" />
279       <inertia ixx="0.1" ixy="0.0" ixz="0.0"
280                iyy="0.1" iyz="0.0"
281                izz="0.1" />
282     </inertial>-->
283     <inertial>
284       <origin xyz="9.0909590e-02 3.8929816e-04 2.2413279e-04"/>
285       <mass value="1.3274562e-01"/>
286       <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"/>
287     </inertial>
288   </link>
289   <!--  Joint 4 -->
290   <joint name="joint4" type="revolute">
291     <parent link="link4"/>
292     <child link="link5"/>
293     <origin rpy="0 0 0" xyz="0.124 0.0 0.0"/>
294     <axis xyz="0 1 0"/>
295     <limit effort="1" lower="-1.79070781255" upper="2.04203522483" velocity="4.8"/>
296   </joint>
297   <transmission name="tran4">
298     <type>transmission_interface/SimpleTransmission</type>
299     <joint name="joint4">
300       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
301     </joint>
302     <actuator name="motor4">
303       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
304       <mechanicalReduction>1</mechanicalReduction>
305     </actuator>
306   </transmission>
307   <!--  Link 5 -->
308   <link name="link5">
309     <visual>
310       <origin rpy="0 0 0" xyz="0 0 0"/>
311       <geometry>
312         <mesh filename="package://open_manipulator_description/meshes/chain_link5.stl" scale="0.001 0.001 0.001"/>
313       </geometry>
314       <material name="grey"/>
315     </visual>
316     <collision>
317       <origin rpy="0 0 0" xyz="0 0 0"/>
318       <geometry>
319         <mesh filename="package://open_manipulator_description/meshes/chain_link5.stl" scale="0.001 0.001 0.001"/>
320       </geometry>
321     </collision>
322     <!--    <inertial>
323       <origin xyz="0 0 0" />
324       <mass value="0.141" />
325       <inertia ixx="0.1" ixy="0.0" ixz="0.0"
326                iyy="0.1" iyz="0.0"
327                izz="0.1" />
328     </inertial>-->
329     <inertial>
330       <origin xyz="4.4206755e-02 3.6839985e-07 8.9142216e-03"/>
331       <mass value="1.4327573e-01"/>
332       <inertia ixx="8.0870749e-05" ixy="0.0" ixz="-1.0157896e-06" iyy="7.5980465e-05" iyz="0.0" izz="9.3127351e-05"/>
333     </inertial>
334   </link>
335   <!--  Gripper link -->
336   <link name="gripper_link">
337     <visual>
338       <origin rpy="0 0 0" xyz="0.0 0.0 0"/>
339       <geometry>
340         <mesh filename="package://open_manipulator_description/meshes/chain_link_grip_l.stl" scale="0.001 0.001 0.001"/>
341       </geometry>
342       <material name="grey"/>
343     </visual>
344     <collision>
345       <origin rpy="0 0 0" xyz="0.0 0.0 0"/>
346       <geometry>
347         <mesh filename="package://open_manipulator_description/meshes/chain_link_grip_l.stl" scale="0.001 0.001 0.001"/>
348       </geometry>
349     </collision>
350     <inertial>
351       <origin xyz="0 0 0"/>
352       <mass value="0.017"/>
353       <inertia ixx="1.0e-03" ixy="0.0" ixz="0.0" iyy="1.0e-03" iyz="0.0" izz="1.0e-03"/>
354     </inertial>
355     <!--     <inertial>
356       <origin xyz="${0.028 + 8.3720668e-03} ${0.0246 + 9.9696160e-03} -4.2836895e-07" />
357       <mass value="3.2218127e-02" />
358       <inertia ixx="9.5568826e-06" ixy="2.8424644e-06" ixz="-3.2829197e-10"
359                iyy="2.2552871e-05" iyz="-3.1463634e-10"
360                izz="1.7605306e-05" />
361     </inertial>-->
362   </link>
363   <!--  Gripper joint -->
364   <joint name="gripper" type="prismatic">
365     <parent link="link5"/>
366     <child link="gripper_link"/>
367     <origin rpy="0 0 0" xyz="0.0817 0.021 0.0"/>
368     <axis xyz="0 1 0"/>
369     <limit effort="1" lower="-0.010" upper="0.019" velocity="4.8"/>
370   </joint>
371   <transmission name="tran5">
372     <type>transmission_interface/SimpleTransmission</type>
373     <joint name="gripper">
374       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
375     </joint>
376     <actuator name="motor5">
377       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
378       <mechanicalReduction>1</mechanicalReduction>
379     </actuator>
380   </transmission>
381   <!--  Gripper link sub -->
382   <link name="gripper_link_sub">
383     <visual>
384       <origin rpy="0 0 0" xyz="0.0 -0.0 0"/>
385       <geometry>
386         <mesh filename="package://open_manipulator_description/meshes/chain_link_grip_r.stl" scale="0.001 0.001 0.001"/>
387       </geometry>
388       <material name="grey"/>
389     </visual>
390     <collision>
391       <origin rpy="0 0 0" xyz="0.0 -0.0 0"/>
392       <geometry>
393         <mesh filename="package://open_manipulator_description/meshes/chain_link_grip_r.stl" scale="0.001 0.001 0.001"/>
394       </geometry>
395     </collision>
396     <inertial>
397       <origin xyz="0 0 0"/>
398       <mass value="0.017"/>
399       <inertia ixx="1.0e-03" ixy="0.0" ixz="0.0" iyy="1.0e-03" iyz="0.0" izz="1.0e-03"/>
400     </inertial>
401     <!--     <inertial>
402       <origin xyz="${0.028 + 8.3720668e-03} ${-0.0246 - 9.9696160e-03} -4.2836895e-07" />
403       <mass value="3.2218127e-02" />
404       <inertia ixx="9.5568826e-06" ixy="2.8424644e-06" ixz="-3.2829197e-10"
405                iyy="2.2552871e-05" iyz="-3.1463634e-10"
406                izz="1.7605306e-05" />
407     </inertial>-->
408   </link>
409   <!--  Gripper joint sub -->
410   <joint name="gripper_sub" type="prismatic">
411     <parent link="link5"/>
412     <child link="gripper_link_sub"/>
413     <origin rpy="0 0 0" xyz="0.0817 -0.021 0"/>
414     <axis xyz="0 -1 0"/>
415     <limit effort="1" lower="-0.010" upper="0.019" velocity="4.8"/>
416     <mimic joint="gripper" multiplier="1"/>
417   </joint>
418   <transmission name="tran6">
419     <type>transmission_interface/SimpleTransmission</type>
420     <joint name="gripper_sub">
421       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
422     </joint>
423     <actuator name="motor6">
424       <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
425       <mechanicalReduction>1</mechanicalReduction>
426     </actuator>
427   </transmission>
428   <!-- end effector joint -->
429   <joint name="end_effector_joint" type="fixed">
430     <origin rpy="0 0 0" xyz="0.126 0.0 0.0"/>
431     <parent link="link5"/>
432     <child link="end_effector_link"/>
433   </joint>
434   <!-- end effector link -->
435   <link name="end_effector_link">
436     <visual>
437       <origin rpy="0 0 0" xyz="0 0 0"/>
438       <geometry>
439         <box size="0.01 0.01 0.01"/>
440       </geometry>
441       <material name="red"/>
442     </visual>
443     <inertial>
444       <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
445       <mass value="0.001"/>
446       <inertia ixx="1.0e-06" ixy="0.0" ixz="0.0" iyy="1.0e-06" iyz="0.0" izz="1.0e-06"/>
447     </inertial>
448   </link>
449   <material name="camera_aluminum">
450     <color rgba="0.5 0.5 0.5 1"/>
451   </material>
452   <!-- camera body, with origin at bottom screw mount -->
453   <joint name="camera_joint" type="fixed">
454     <origin rpy="0 0 0" xyz="-0.02 -0.018 0.055"/>
455     <parent link="gripper_link"/>
456     <child link="camera_bottom_screw_frame"/>
457   </joint>
458   <link name="camera_bottom_screw_frame"/>
459   <joint name="camera_link_joint" type="fixed">
460     <origin rpy="0 0 0" xyz="0 0.0175 0.0125"/>
461     <parent link="camera_bottom_screw_frame"/>
462     <child link="camera_link"/>
463   </joint>
464   <link name="camera_link">
465     <visual>
466       <origin rpy="1.57079632679 0 1.57079632679" xyz="0.0149 -0.0175 0"/>
467       <geometry>
468         <!-- <box size="${d435_cam_width} ${d435_cam_height} ${d435_cam_depth}"/> -->
469         <mesh filename="package://realsense2_description/meshes/d435.dae"/>
470         <!--<mesh filename="package://realsense2_description/meshes/d435/d435.dae" />-->
471       </geometry>
472       <material name="camera_aluminum"/>
473     </visual>
474     <collision>
475       <origin rpy="0 0 0" xyz="0 -0.0175 0"/>
476       <geometry>
477         <box size="0.02505 0.09 0.025"/>
478       </geometry>
479     </collision>
480     <inertial>
481       <!-- The following are not reliable values, and should not be used for modeling -->
482       <mass value="0.564"/>
483       <origin xyz="0 0 0"/>
484       <inertia ixx="0.003881243" ixy="0.0" ixz="0.0" iyy="0.000498940" iyz="0.0" izz="0.003879257"/>
485     </inertial>
486   </link>
487   <!-- camera depth joints and links -->
488   <joint name="camera_depth_joint" type="fixed">
489     <origin rpy="0 0 0" xyz="0 0 0"/>
490     <parent link="camera_link"/>
491     <child link="camera_depth_frame"/>
492   </joint>
493   <link name="camera_depth_frame"/>
494   <joint name="camera_depth_optical_joint" type="fixed">
495     <origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0"/>
496     <parent link="camera_depth_frame"/>
497     <child link="camera_depth_optical_frame"/>
498   </joint>
499   <link name="camera_depth_optical_frame"/>
500   <!-- camera left IR joints and links -->
501   <joint name="camera_left_ir_joint" type="fixed">
502     <origin rpy="0 0 0" xyz="0 0.0 0"/>
503     <parent link="camera_depth_frame"/>
504     <child link="camera_left_ir_frame"/>
505   </joint>
506   <link name="camera_left_ir_frame"/>
507   <joint name="camera_left_ir_optical_joint" type="fixed">
508     <origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0"/>
509     <parent link="camera_left_ir_frame"/>
510     <child link="camera_left_ir_optical_frame"/>
511   </joint>
512   <link name="camera_left_ir_optical_frame"/>
513   <!-- camera right IR joints and links -->
514   <joint name="camera_right_ir_joint" type="fixed">
515     <origin rpy="0 0 0" xyz="0 -0.05 0"/>
516     <parent link="camera_depth_frame"/>
517     <child link="camera_right_ir_frame"/>
518   </joint>
519   <link name="camera_right_ir_frame"/>
520   <joint name="camera_right_ir_optical_joint" type="fixed">
521     <origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0"/>
522     <parent link="camera_right_ir_frame"/>
523     <child link="camera_right_ir_optical_frame"/>
524   </joint>
525   <link name="camera_right_ir_optical_frame"/>
526   <!-- camera color joints and links -->
527   <joint name="camera_color_joint" type="fixed">
528     <origin rpy="0 0 0" xyz="0 0.015 0"/>
529     <parent link="camera_depth_frame"/>
530     <child link="camera_color_frame"/>
531   </joint>
532   <link name="camera_color_frame"/>
533   <joint name="camera_color_optical_joint" type="fixed">
534     <origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 0 0"/>
535     <parent link="camera_color_frame"/>
536     <child link="camera_color_optical_frame"/>
537   </joint>
538   <link name="camera_color_optical_frame"/>
539 </robot>