/
irb6600_with_linear_track_workspace.xacro
41 lines (34 loc) · 1.51 KB
/
irb6600_with_linear_track_workspace.xacro
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
<?xml version="1.0" ?>
<robot name="framefab_irb6600_workspace" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:property name="half_pi" value="1.5707963267948966"/>
<xacro:include filename="$(find framefab_irb6600_support)/urdf/resources/materials.xacro"/>
<xacro:include filename="$(find abb_irb6600_support)/urdf/irb6640_macro.xacro"/>
<xacro:include filename="$(find asw_end_effector)/urdf/asw_eef_macro.xacro"/>
<xacro:include filename="$(find ucla_linear_axis)/urdf/ucla_linear_axis_macro.xacro"/>
<!-- <xacro:include filename="$(find framefab_irb6600_support)/urdf/simple_linear_track_demo_cell_macro.xacro"/>-->
<xacro:abb_irb6640 prefix="robot_"/>
<xacro:asw_eef prefix="eef_"/>
<xacro:ucla_linear_axis prefix="linear_axis_"/>
<!-- <xacro:simple_linear_track_demo_cell prefix=""/>-->
<!-- Link list -->
<link name="base_link"/>
<!-- End of link list -->
<!-- Joint list -->
<!--bind the rail to word_frame, can be disabled if using modile platform-->
<joint name="linear_axis_to_base_link" type="fixed">
<origin xyz="0 0 0" rpy="0 0 ${half_pi}"/>
<parent link="base_link"/>
<child link="linear_axis_base_link"/>
</joint>
<joint name="robot_to_linear_axis" type="fixed">
<origin xyz="0 0 0" rpy="0 0 -${half_pi}"/>
<parent link="linear_axis_robot_mount"/>
<child link="robot_base_link"/>
</joint>
<joint name="ee_to_robot" type="fixed">
<parent link="robot_tool0"/>
<child link="eef_base_link"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
</joint>
<!-- End of joint list -->
</robot>