-
Notifications
You must be signed in to change notification settings - Fork 321
/
Copy pathhand.xacro
86 lines (86 loc) · 2.93 KB
/
hand.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
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
<?xml version="1.0" encoding="utf-8"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="hand">
<!-- safety_distance: Minimum safety distance in [m] by which the collision volumes are expanded and which is enforced during robot motions -->
<xacro:macro name="hand" params="connected_to:='' ns:='' rpy:='0 0 0' xyz:='0 0 0' safety_distance:=0">
<xacro:unless value="${connected_to == ''}">
<joint name="${ns}_hand_joint" type="fixed">
<parent link="${connected_to}"/>
<child link="${ns}_hand"/>
<origin xyz="${xyz}" rpy="${rpy}"/>
</joint>
</xacro:unless>
<link name="${ns}_hand">
<visual>
<geometry>
<mesh filename="package://franka_description/meshes/visual/hand.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0.04" rpy="0 ${pi/2} ${pi/2}"/>
<geometry>
<cylinder radius="${0.04+safety_distance}" length="0.1" />
</geometry>
</collision>
<collision>
<origin xyz="0 -0.05 0.04" rpy="0 0 0"/>
<geometry>
<sphere radius="${0.04+safety_distance}" />
</geometry>
</collision>
<collision>
<origin xyz="0 0.05 0.04" rpy="0 0 0"/>
<geometry>
<sphere radius="${0.04+safety_distance}" />
</geometry>
</collision>
<collision>
<origin xyz="0 0 0.1" rpy="0 ${pi/2} ${pi/2}"/>
<geometry>
<cylinder radius="${0.02+safety_distance}" length="0.1" />
</geometry>
</collision>
<collision>
<origin xyz="0 -0.05 0.1" rpy="0 0 0"/>
<geometry>
<sphere radius="${0.02+safety_distance}" />
</geometry>
</collision>
<collision>
<origin xyz="0 0.05 0.1" rpy="0 0 0"/>
<geometry>
<sphere radius="${0.02+safety_distance}" />
</geometry>
</collision>
</link>
<link name="${ns}_leftfinger">
<visual>
<geometry>
<mesh filename="package://franka_description/meshes/visual/finger.dae"/>
</geometry>
</visual>
</link>
<link name="${ns}_rightfinger">
<visual>
<origin xyz="0 0 0" rpy="0 0 ${pi}"/>
<geometry>
<mesh filename="package://franka_description/meshes/visual/finger.dae"/>
</geometry>
</visual>
</link>
<joint name="${ns}_finger_joint1" type="prismatic">
<parent link="${ns}_hand"/>
<child link="${ns}_leftfinger"/>
<origin xyz="0 0 0.0584" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
<limit effort="20" lower="0.0" upper="0.04" velocity="0.2"/>
</joint>
<joint name="${ns}_finger_joint2" type="prismatic">
<parent link="${ns}_hand"/>
<child link="${ns}_rightfinger"/>
<origin xyz="0 0 0.0584" rpy="0 0 0"/>
<axis xyz="0 -1 0"/>
<limit effort="20" lower="0.0" upper="0.04" velocity="0.2"/>
<mimic joint="${ns}_finger_joint1" />
</joint>
</xacro:macro>
</robot>