-
Notifications
You must be signed in to change notification settings - Fork 310
/
franka_arm.xacro
139 lines (120 loc) · 6.19 KB
/
franka_arm.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
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
<?xml version='1.0' encoding='utf-8'?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="panda">
<xacro:include filename="$(find franka_description)/robots/common/utils.xacro" />
<!-- safety_distance: Minimum safety distance in [m] by which the collision volumes are expanded and which is enforced during robot motions -->
<!-- arm_id: Namespace of the robot arm. Serves to differentiate between arms in case of multiple instances. -->
<!-- joint_limits: description of the joint limits that comes from a YAML file. Example definition: ${xacro.load_yaml('$(find franka_description)/robots/fr3/joint_limits.yaml')} -->
<xacro:macro name="franka_arm" params="arm_id:='panda' description_pkg:='franka_description' connected_to:='' xyz:='0 0 0' rpy:='0 0 0' gazebo:=false safety_distance:=0 joint_limits" >
<xacro:unless value="${not connected_to}">
<joint name="${arm_id}_joint_${connected_to}" type="fixed">
<parent link="${connected_to}"/>
<child link="${arm_id}_link0"/>
<origin rpy="${rpy}" xyz="${xyz}"/>
</joint>
</xacro:unless>
<xacro:link_with_sc name="link0" gazebo="${gazebo}">
<self_collision_geometries>
<xacro:collision_capsule xyz="-0.075 0 0.06" direction="x" radius="${0.06+safety_distance}" length="0.03" />
</self_collision_geometries>
</xacro:link_with_sc>
<xacro:link_with_sc name="link1" gazebo="${gazebo}">
<self_collision_geometries>
<xacro:collision_capsule xyz="0 0 -191.5e-3" radius="${0.06+safety_distance}" length="0.283" />
</self_collision_geometries>
</xacro:link_with_sc>
<joint name="${arm_id}_joint1" type="revolute">
<origin rpy="0 0 0" xyz="0 0 0.333" />
<parent link="${arm_id}_link0" />
<child link="${arm_id}_link1" />
<axis xyz="0 0 1" />
<xacro:franka-limits name="joint1" config="${joint_limits}" />
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16" />
</joint>
<xacro:link_with_sc name="link2" gazebo="${gazebo}">
<self_collision_geometries>
<xacro:collision_capsule xyz="0 0 0" radius="${0.06+safety_distance}" length="0.12" />
</self_collision_geometries>
</xacro:link_with_sc>
<joint name="${arm_id}_joint2" type="revolute">
<origin rpy="${-pi/2} 0 0" xyz="0 0 0" />
<parent link="${arm_id}_link1" />
<child link="${arm_id}_link2" />
<axis xyz="0 0 1" />
<xacro:franka-limits name="joint2" config="${joint_limits}" />
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16" />
</joint>
<xacro:link_with_sc name="link3" gazebo="${gazebo}">
<self_collision_geometries>
<xacro:collision_capsule xyz="0 0 -0.145" radius="${0.06+safety_distance}" length="0.15" />
</self_collision_geometries>
</xacro:link_with_sc>
<joint name="${arm_id}_joint3" type="revolute">
<origin rpy="${pi/2} 0 0" xyz="0 -0.316 0" />
<parent link="${arm_id}_link2" />
<child link="${arm_id}_link3" />
<axis xyz="0 0 1" />
<xacro:franka-limits name="joint3" config="${joint_limits}" />
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16" />
</joint>
<xacro:link_with_sc name="link4" gazebo="${gazebo}">
<self_collision_geometries>
<xacro:collision_capsule xyz="0 0 0" radius="${0.06+safety_distance}" length="0.12" />
</self_collision_geometries>
</xacro:link_with_sc>
<joint name="${arm_id}_joint4" type="revolute">
<origin rpy="${pi/2} 0 0" xyz="0.0825 0 0" />
<parent link="${arm_id}_link3" />
<child link="${arm_id}_link4" />
<axis xyz="0 0 1" />
<xacro:franka-limits name="joint4" config="${joint_limits}" />
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16" />
</joint>
<xacro:link_with_sc name="link5" gazebo="${gazebo}">
<self_collision_geometries>
<xacro:collision_capsule xyz="0 0 -0.26" radius="${0.060+safety_distance}" length="0.10" />
<xacro:collision_capsule xyz="0 0.08 -0.13" radius="${0.025+safety_distance}" length="0.14" />
</self_collision_geometries>
</xacro:link_with_sc>
<joint name="${arm_id}_joint5" type="revolute">
<origin rpy="${-pi/2} 0 0" xyz="-0.0825 0.384 0" />
<parent link="${arm_id}_link4" />
<child link="${arm_id}_link5" />
<axis xyz="0 0 1" />
<xacro:franka-limits name="joint5" config="${joint_limits}" />
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16" />
</joint>
<xacro:link_with_sc name="link6" gazebo="${gazebo}">
<self_collision_geometries>
<xacro:collision_capsule xyz="0 0 -0.03" radius="${0.05+safety_distance}" length="0.08" />
</self_collision_geometries>
</xacro:link_with_sc>
<joint name="${arm_id}_joint6" type="revolute">
<origin rpy="${pi/2} 0 0" xyz="0 0 0" />
<parent link="${arm_id}_link5" />
<child link="${arm_id}_link6" />
<axis xyz="0 0 1" />
<xacro:franka-limits name="joint6" config="${joint_limits}" />
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16" />
</joint>
<xacro:link_with_sc name="link7" gazebo="${gazebo}" rpy="0 0 ${pi/4}">
<self_collision_geometries>
<xacro:collision_capsule xyz="0 0 0.01" direction="z" radius="${0.04+safety_distance}" length="0.14" />
<xacro:collision_capsule xyz="0.06 0 0.082" direction="x" radius="${0.03+safety_distance}" length="0.01" />
</self_collision_geometries>
</xacro:link_with_sc>
<joint name="${arm_id}_joint7" type="revolute">
<origin rpy="${pi/2} 0 0" xyz="0.088 0 0"/>
<parent link="${arm_id}_link6"/>
<child link="${arm_id}_link7"/>
<axis xyz="0 0 1"/>
<xacro:franka-limits name="joint7" config="${joint_limits}" />
<dynamics D="1" K="7000" damping="0.003" friction="0.0" mu_coulomb="0" mu_viscous="16"/>
</joint>
<link name="${arm_id}_link8"/>
<joint name="${arm_id}_joint8" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.107"/>
<parent link="${arm_id}_link7"/>
<child link="${arm_id}_link8"/>
</joint>
</xacro:macro>
</robot>