-
Notifications
You must be signed in to change notification settings - Fork 321
/
Copy pathutils.xacro
241 lines (226 loc) · 12.2 KB
/
utils.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
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- Load inertial properties. Property is implicitly passed to macros. -->
<xacro:property name="inertial_config" value="$(find franka_description)/robots/common/inertial.yaml"/>
<xacro:property name="inertial" value="${xacro.load_yaml(inertial_config)}"/>
<!-- ============================================================== -->
<!-- Macro to add an <inertial> tag based on yaml-load properties -->
<!-- -->
<!-- name: Name of the robot link (without prefix) -->
<!-- inertial: Dictionary of inertia properties (see inertial.yaml) -->
<!-- ============================================================== -->
<xacro:macro name="inertial_props" params="name inertial:=^">
<xacro:unless value="${name in inertial}">${xacro.warning('No inertia properties defined for: ' + name)}</xacro:unless>
<xacro:if value="${name in inertial}">
<!-- Access inertia properties of link 'name' -->
<xacro:property name="inertial" value="${inertial[name]}" lazy_eval="false" />
<inertial>
<origin rpy="${inertial.origin.rpy}" xyz="${inertial.origin.xyz}" />
<mass value="${inertial.mass}" />
<xacro:property name="I" value="${inertial.inertia}" />
<inertia ixx="${I.xx}" ixy="${I.xy}" ixz="${I.xz}" iyy="${I.yy}" iyz="${I.yz}" izz="${I.zz}" />
</inertial>
</xacro:if>
</xacro:macro>
<!-- ========================================================== -->
<!-- Macro to add a single link, both with -->
<!-- * detailed meshes for environmental collision checking -->
<!-- * and coarse geometry models for self-collision checking -->
<!-- (only if 'gazebo' param is set) -->
<!-- -->
<!-- name: Name of the robot link (without prefix) -->
<!-- rpy: Rotation of the *_sc link relative to parent [rad] -->
<!-- self_collision_geometries: self <collision> models -->
<!-- ========================================================== -->
<xacro:macro name="link_with_sc" params="name prefix=${arm_id}_ rpy:='0 0 0' **self_collision_geometries gazebo:=false">
<!-- sub-link defining detailed meshes for collision with environment -->
<link name="${prefix}${name}">
<visual>
<geometry>
<mesh filename="package://${description_pkg}/meshes/visual/${name}.dae" />
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://franka_description/meshes/collision/${name}.stl" />
</geometry>
</collision>
<xacro:if value="${gazebo}">
<xacro:inertial_props name="${name}" />
</xacro:if>
</link>
<!-- sub-link defining coarse geometries of real robot's internal self-collision -->
<link name="${prefix}${name}_sc">
<xacro:unless value="${gazebo}">
<xacro:insert_block name="self_collision_geometries" />
</xacro:unless>
</link>
<!-- fixed joint between both sub-links -->
<joint name="${prefix}${name}_sc_joint" type="fixed">
<origin rpy="${rpy}" />
<parent link="${prefix}${name}" />
<child link="${prefix}${name}_sc" />
</joint>
</xacro:macro>
<!-- =========================================================== -->
<!-- Add a <collision> tag with a capsule, made from a cylinder -->
<!-- with two spheres at its caps. The capsule will always be -->
<!-- aligned with the axis of 'direction' you pass along. -->
<!-- -->
<!-- radius: Radii of both the cylinder and both spheres [m] -->
<!-- length: Length of the cylinder/distance between the centers -->
<!-- of the spheres. NOT overall length of capsule! -->
<!-- xyz: Position of the center of the capsule/cylinder -->
<!-- direction: One of { x, y, z, -x, -y, -z } -->
<!-- =========================================================== -->
<xacro:macro name="collision_capsule" params="radius length xyz:='0 0 0' direction:='z'">
<xacro:property name="r" value="${pi/2.0 if 'y' in direction else 0}" />
<xacro:property name="p" value="${pi/2.0 if 'x' in direction else 0}" />
<xacro:property name="y" value="0" />
<xacro:property name="x" value="${xyz.split(' ')[0]}" />
<xacro:property name="y" value="${xyz.split(' ')[1]}" />
<xacro:property name="z" value="${xyz.split(' ')[2]}" />
<!-- Sphere center offsets from center of cylinder -->
<xacro:property name="sx" value="${length / 2.0 if 'x' in direction else 0}" />
<xacro:property name="sy" value="${length / 2.0 if 'y' in direction else 0}" />
<xacro:property name="sz" value="${length / 2.0 if 'z' in direction else 0}" />
<collision>
<origin xyz="${x} ${y} ${z}" rpy="${r} ${p} ${y}"/>
<geometry>
<cylinder radius="${radius}" length="${length}" />
</geometry>
</collision>
<collision>
<origin xyz="${x+sx} ${y+sy} ${z+sz}" />
<geometry>
<sphere radius="${radius}" />
</geometry>
</collision>
<collision>
<origin xyz="${x-sx} ${y-sy} ${z-sz}" />
<geometry>
<sphere radius="${radius}" />
</geometry>
</collision>
</xacro:macro>
<!-- ========================================================== -->
<!-- Adds the required tags to simulate one joint in gazebo -->
<!-- -->
<!-- joint - Name of the panda joint to simulate -->
<!-- transmission - type of the transmission of the joint -->
<!-- ========================================================== -->
<xacro:macro name="gazebo-joint" params="joint transmission:=hardware_interface/EffortJointInterface">
<gazebo reference="${joint}">
<!-- Needed for ODE to output external wrenches on joints -->
<provideFeedback>true</provideFeedback>
</gazebo>
<transmission name="${joint}_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${joint}">
<hardwareInterface>${transmission}</hardwareInterface>
</joint>
<actuator name="${joint}_motor">
<hardwareInterface>${transmission}</hardwareInterface>
</actuator>
</transmission>
</xacro:macro>
<xacro:macro name="gazebo-friction" params="link mu">
<gazebo reference="${link}">
<collision>
<max_contacts>10</max_contacts>
<surface>
<contact>
<ode>
<!-- These two parameter need application specific tuning. -->
<!-- Usually you want no "snap out" velocity and a generous -->
<!-- penetration depth to keep the grasping stable -->
<max_vel>0</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
<friction>
<ode>
<mu>${mu}</mu>
<mu2>${mu}</mu2>
</ode>
</friction>
<bounce/>
</surface>
</collision>
</gazebo>
</xacro:macro>
<!-- ========================================================== -->
<!-- Adds the required tags to provide a `FrankaStateInterface` -->
<!-- when simulating with franka_hw_sim plugin -->
<!-- -->
<!-- arm_id - Arm ID of the panda to simulate (default 'panda') -->
<!-- ========================================================== -->
<xacro:macro name="transmission-franka-state" params="arm_id:=panda">
<transmission name="${arm_id}_franka_state">
<type>franka_hw/FrankaStateInterface</type>
<joint name="${arm_id}_joint1"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
<joint name="${arm_id}_joint2"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
<joint name="${arm_id}_joint3"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
<joint name="${arm_id}_joint4"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
<joint name="${arm_id}_joint5"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
<joint name="${arm_id}_joint6"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
<joint name="${arm_id}_joint7"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></joint>
<actuator name="${arm_id}_motor1"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
<actuator name="${arm_id}_motor2"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
<actuator name="${arm_id}_motor3"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
<actuator name="${arm_id}_motor4"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
<actuator name="${arm_id}_motor5"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
<actuator name="${arm_id}_motor6"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
<actuator name="${arm_id}_motor7"><hardwareInterface>franka_hw/FrankaStateInterface</hardwareInterface></actuator>
</transmission>
</xacro:macro>
<!-- ============================================================ -->
<!-- Adds the required tags to provide a `FrankaModelInterface` -->
<!-- when simulating with franka_hw_sim plugin -->
<!-- -->
<!-- arm_id - Arm ID of the panda to simulate (default 'panda') -->
<!-- root - Joint name of the base of the robot -->
<!-- tip - Joint name of the tip of the robot (flange or hand) -->
<!-- ============================================================ -->
<xacro:macro name="transmission-franka-model" params="arm_id:=panda root:=panda_joint1 tip:=panda_joint7">
<transmission name="${arm_id}_franka_model">
<type>franka_hw/FrankaModelInterface</type>
<joint name="${root}">
<role>root</role>
<hardwareInterface>franka_hw/FrankaModelInterface</hardwareInterface>
</joint>
<joint name="${tip}">
<role>tip</role>
<hardwareInterface>franka_hw/FrankaModelInterface</hardwareInterface>
</joint>
<actuator name="${root}_motor_root"><hardwareInterface>franka_hw/FrankaModelInterface</hardwareInterface></actuator>
<actuator name="${tip}_motor_tip" ><hardwareInterface>franka_hw/FrankaModelInterface</hardwareInterface></actuator>
</transmission>
</xacro:macro>
<xacro:macro name="inertia-cylinder" params="mass radius h">
<inertial>
<mass value="${mass}" />
<inertia ixx="${1./12 * mass * (3 * radius**2 + h**2)}" ixy = "0" ixz = "0"
iyy="${1./12 * mass * (3 * radius**2 + h**2)}" iyz = "0"
izz="${1./2 * mass * radius**2}" />
</inertial>
</xacro:macro>
<!-- ========================================================================= -->
<!-- Adds the <limit ... /> & <safety_controller/> tags given a config file -->
<!-- of joint limits -->
<!-- -->
<!-- config - YAML struct defining joint limits (e.g. panda/joint_limits.yaml) -->
<!-- name - Name of the joint for which to add limits to -->
<!-- ========================================================================= -->
<xacro:macro name="franka-limits" params="config name">
<xacro:property name="limits" value="${config[name]['limit']}" lazy_eval="false" />
<limit lower="${limits.lower}"
upper="${limits.upper}"
effort="${limits.effort}"
velocity="${limits.velocity}" />
<safety_controller k_position="100.0"
k_velocity="40.0"
soft_lower_limit="${limits.lower}"
soft_upper_limit="${limits.upper}" />
</xacro:macro>
</robot>