-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathreach_study.xacro
46 lines (40 loc) · 1.39 KB
/
reach_study.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
42
43
44
45
46
<?xml version="1.0" ?>
<robot name="reach_study" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find reach_ros)/demo/model/motoman_sia20d/motoman_sia20d_macro.xacro" />
<link name="world"/>
<!-- TODO: Define the link(s) and joint(s) needed to connect the mobile base to the world frame in such a way that it can translate in the x-y plane and rotate about the z-axis -->
<xacro:property name="height" value="0.3"/>
<xacro:property name="radius" value="0.4" />
<link name="mobile_base">
<visual>
<origin xyz="0.0 0.0 ${height / 2.0}"/>
<geometry>
<cylinder radius="${radius}" length="${height}"/>
</geometry>
</visual>
<collision>
<origin xyz="0.0 0.0 ${height / 2.0}"/>
<geometry>
<cylinder radius="${radius}" length="${height}"/>
</geometry>
</collision>
</link>
<xacro:motoman_sia20d prefix=""/>
<joint name="mobile_base_to_robot" type="fixed">
<parent link="mobile_base"/>
<child link="base_link"/>
<origin xyz="0.0 0.0 ${height}"/>
</joint>
<link name="tcp"/>
<joint name="tool0_to_tcp" type="fixed">
<parent link="tool0"/>
<child link="tcp"/>
<origin xyz="0 0 0.1"/>
</joint>
<link name="blade"/>
<joint name="world_to_blade" type="fixed">
<parent link="world"/>
<child link="blade"/>
<origin xyz="1.0 1.0 0.5" rpy="0 0 ${radians(-90)}"/>
</joint>
</robot>