-
Notifications
You must be signed in to change notification settings - Fork 131
/
Copy pathur_macro.xacro
400 lines (377 loc) · 17.1 KB
/
ur_macro.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
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<!--
Base UR robot series xacro macro.
NOTE this is NOT a URDF. It cannot directly be loaded by consumers
expecting a flattened '.urdf' file. See the top-level '.xacro' for that
(but note that .xacro must still be processed by the xacro command).
This file models the base kinematic chain of a UR robot, which then gets
parameterised by various configuration files to convert it into a UR3(e),
UR5(e), UR10(e) or UR16e.
NOTE the default kinematic parameters (i.e., link lengths, frame locations,
offsets, etc) do not correspond to any particular robot. They are defaults
only. There WILL be non-zero offsets between the Forward Kinematics results
in TF (i.e., robot_state_publisher) and the values reported by the Teach
Pendant.
For accurate (and robot-specific) transforms, the 'kinematics_parameters_file'
parameter MUST point to a .yaml file containing the appropriate values for
the targeted robot.
If using the UniversalRobots/Universal_Robots_ROS_Driver, follow the steps
described in the readme of that repository to extract the kinematic
calibration from the controller and generate the required .yaml file.
Main author of the migration to yaml configs Ludovic Delval.
Contributors to previous versions (in no particular order)
- Denis Stogl
- Lovro Ivanov
- Felix Messmer
- Kelsey Hawkins
- Wim Meeussen
- Shaun Edwards
- Nadia Hammoudeh Garcia
- Dave Hershberger
- G. vd. Hoorn
- Philip Long
- Dave Coleman
- Miguel Prada
- Mathias Luedtke
- Marcel Schnirring
- Felix von Drigalski
- Felix Exner
- Jimmy Da Silva
- Ajit Krisshna N L
- Muhammad Asif Rana
-->
<xacro:include filename="$(find ur_description)/urdf/inc/ur_transmissions.xacro" />
<xacro:include filename="$(find ur_description)/urdf/inc/ur_common.xacro" />
<xacro:macro name="ur_robot" params="
name
tf_prefix
parent
*origin
joint_limits_parameters_file
kinematics_parameters_file
physical_parameters_file
visual_parameters_file
transmission_hw_interface:=hardware_interface/PositionJointInterface
safety_limits:=false
safety_pos_margin:=0.15
safety_k_position:=20
use_mock_hardware:=false
mock_sensor_commands:=false
sim_gazebo:=false
sim_ignition:=false
headless_mode:=false
initial_positions:=${dict(shoulder_pan_joint=0.0,shoulder_lift_joint=-1.57,elbow_joint=0.0,wrist_1_joint=-1.57,wrist_2_joint=0.0,wrist_3_joint=0.0)}
use_tool_communication:=false
tool_voltage:=0
tool_parity:=0
tool_baud_rate:=115200
tool_stop_bits:=1
tool_rx_idle_chars:=1.5
tool_tx_idle_chars:=3.5
tool_device_name:=/tmp/ttyUR
tool_tcp_port:=54321
robot_ip:=0.0.0.0
script_filename:=to_be_filled_by_ur_robot_driver
output_recipe_filename:=to_be_filled_by_ur_robot_driver
input_recipe_filename:=to_be_filled_by_ur_robot_driver
reverse_port:=50001
script_sender_port:=50002
reverse_ip:=0.0.0.0
script_command_port:=50004
trajectory_port:=50003
non_blocking_read:=false
keep_alive_count:=2"
>
<!-- Load configuration data from the provided .yaml files -->
<xacro:read_model_data
joint_limits_parameters_file="${joint_limits_parameters_file}"
kinematics_parameters_file="${kinematics_parameters_file}"
physical_parameters_file="${physical_parameters_file}"
visual_parameters_file="${visual_parameters_file}"
force_abs_paths="${sim_gazebo or sim_ignition}"/>
<!-- ros2 control include -->
<xacro:include filename="$(find ur_description)/urdf/ur.ros2_control.xacro" />
<!-- ros2 control instance -->
<xacro:ur_ros2_control
name="${name}"
use_mock_hardware="${use_mock_hardware}"
initial_positions="${initial_positions}"
mock_sensor_commands="${mock_sensor_commands}"
headless_mode="${headless_mode}"
sim_gazebo="${sim_gazebo}"
sim_ignition="${sim_ignition}"
script_filename="${script_filename}"
output_recipe_filename="${output_recipe_filename}"
input_recipe_filename="${input_recipe_filename}"
tf_prefix="${tf_prefix}"
hash_kinematics="${kinematics_hash}"
robot_ip="${robot_ip}"
use_tool_communication="${use_tool_communication}"
tool_voltage="${tool_voltage}"
tool_parity="${tool_parity}"
tool_baud_rate="${tool_baud_rate}"
tool_stop_bits="${tool_stop_bits}"
tool_rx_idle_chars="${tool_rx_idle_chars}"
tool_tx_idle_chars="${tool_tx_idle_chars}"
tool_device_name="${tool_device_name}"
tool_tcp_port="${tool_tcp_port}"
reverse_port="${reverse_port}"
script_sender_port="${script_sender_port}"
reverse_ip="${reverse_ip}"
script_command_port="${script_command_port}"
trajectory_port="${trajectory_port}"
non_blocking_read="${non_blocking_read}"
keep_alive_count="${keep_alive_count}"
/>
<!-- Add URDF transmission elements (for ros_control) -->
<!--<xacro:ur_arm_transmission prefix="${prefix}" hw_interface="${transmission_hw_interface}" />-->
<!-- Placeholder for ros2_control transmission which don't yet exist -->
<!-- links - main serial chain -->
<link name="${tf_prefix}base_link"/>
<link name="${tf_prefix}base_link_inertia">
<visual>
<origin xyz="0 0 0" rpy="0 0 ${pi}"/>
<geometry>
<xacro:get_mesh name="base" type="visual"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 ${pi}"/>
<geometry>
<xacro:get_mesh name="base" type="collision"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="${base_inertia_radius}" length="${base_inertia_length}" mass="${base_mass}">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:cylinder_inertial>
</link>
<link name="${tf_prefix}shoulder_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 ${pi}"/>
<geometry>
<xacro:get_mesh name="shoulder" type="visual"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 ${pi}"/>
<geometry>
<xacro:get_mesh name="shoulder" type="collision"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="${shoulder_inertia_radius}" length="${shoulder_inertia_length}" mass="${shoulder_mass}">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:cylinder_inertial>
</link>
<link name="${tf_prefix}upper_arm_link">
<visual>
<origin xyz="0 0 ${shoulder_offset}" rpy="${pi/2} 0 ${-pi/2}"/>
<geometry>
<xacro:get_mesh name="upper_arm" type="visual"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 ${shoulder_offset}" rpy="${pi/2} 0 ${-pi/2}"/>
<geometry>
<xacro:get_mesh name="upper_arm" type="collision"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="${upperarm_inertia_radius}" length="${upperarm_inertia_length}" mass="${upper_arm_mass}">
<origin xyz="${-0.5 * upperarm_inertia_length} 0.0 ${upper_arm_inertia_offset}" rpy="0 ${pi/2} 0" />
</xacro:cylinder_inertial>
</link>
<link name="${tf_prefix}forearm_link">
<visual>
<origin xyz="0 0 ${elbow_offset}" rpy="${pi/2} 0 ${-pi/2}"/>
<geometry>
<xacro:get_mesh name="forearm" type="visual"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 ${elbow_offset}" rpy="${pi/2} 0 ${-pi/2}"/>
<geometry>
<xacro:get_mesh name="forearm" type="collision"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="${forearm_inertia_radius}" length="${forearm_inertia_length}" mass="${forearm_mass}">
<origin xyz="${-0.5 * forearm_inertia_length} 0.0 ${elbow_offset}" rpy="0 ${pi/2} 0" />
</xacro:cylinder_inertial>
</link>
<link name="${tf_prefix}wrist_1_link">
<xacro:get_visual_params name="wrist_1" type="visual_offset"/>
<visual>
<origin xyz="0 0 ${visual_params}" rpy="${pi/2} 0 0"/>
<geometry>
<xacro:get_mesh name="wrist_1" type="visual"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 ${visual_params}" rpy="${pi/2} 0 0"/>
<geometry>
<xacro:get_mesh name="wrist_1" type="collision"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="${wrist_1_inertia_radius}" length="${wrist_1_inertia_length}" mass="${wrist_1_mass}">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:cylinder_inertial>
</link>
<link name="${tf_prefix}wrist_2_link">
<xacro:get_visual_params name="wrist_2" type="visual_offset"/>
<visual>
<origin xyz="0 0 ${visual_params}" rpy="0 0 0"/>
<geometry>
<xacro:get_mesh name="wrist_2" type="visual"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 ${visual_params}" rpy="0 0 0"/>
<geometry>
<xacro:get_mesh name="wrist_2" type="collision"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="${wrist_2_inertia_radius}" length="${wrist_2_inertia_length}" mass="${wrist_2_mass}">
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:cylinder_inertial>
</link>
<link name="${tf_prefix}wrist_3_link">
<xacro:get_visual_params name="wrist_3" type="visual_offset"/>
<visual>
<origin xyz="0 0 ${visual_params}" rpy="${pi/2} 0 0"/>
<geometry>
<xacro:get_mesh name="wrist_3" type="visual"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 ${visual_params}" rpy="${pi/2} 0 0"/>
<geometry>
<xacro:get_mesh name="wrist_3" type="collision"/>
</geometry>
</collision>
<xacro:cylinder_inertial radius="${wrist_3_inertia_radius}" length="${wrist_3_inertia_length}" mass="${wrist_3_mass}">
<origin xyz="0.0 0.0 ${-0.5 * wrist_3_inertia_length}" rpy="0 0 0" />
</xacro:cylinder_inertial>
</link>
<!-- base_joint fixes base_link to the environment -->
<joint name="${tf_prefix}base_joint" type="fixed">
<xacro:insert_block name="origin" />
<parent link="${parent}" />
<child link="${tf_prefix}base_link" />
</joint>
<!-- joints - main serial chain -->
<joint name="${tf_prefix}base_link-base_link_inertia" type="fixed">
<parent link="${tf_prefix}base_link" />
<child link="${tf_prefix}base_link_inertia" />
<!-- 'base_link' is REP-103 aligned (so X+ forward), while the internal
frames of the robot/controller have X+ pointing backwards.
Use the joint between 'base_link' and 'base_link_inertia' (a dummy
link/frame) to introduce the necessary rotation over Z (of pi rad).
-->
<origin xyz="0 0 0" rpy="0 0 ${pi}" />
</joint>
<joint name="${tf_prefix}shoulder_pan_joint" type="revolute">
<parent link="${tf_prefix}base_link_inertia" />
<child link="${tf_prefix}shoulder_link" />
<origin xyz="${shoulder_x} ${shoulder_y} ${shoulder_z}" rpy="${shoulder_roll} ${shoulder_pitch} ${shoulder_yaw}" />
<axis xyz="0 0 1" />
<limit lower="${shoulder_pan_lower_limit}" upper="${shoulder_pan_upper_limit}"
effort="${shoulder_pan_effort_limit}" velocity="${shoulder_pan_velocity_limit}"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${shoulder_pan_lower_limit + safety_pos_margin}" soft_upper_limit="${shoulder_pan_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="${tf_prefix}shoulder_lift_joint" type="revolute">
<parent link="${tf_prefix}shoulder_link" />
<child link="${tf_prefix}upper_arm_link" />
<origin xyz="${upper_arm_x} ${upper_arm_y} ${upper_arm_z}" rpy="${upper_arm_roll} ${upper_arm_pitch} ${upper_arm_yaw}" />
<axis xyz="0 0 1" />
<limit lower="${shoulder_lift_lower_limit}" upper="${shoulder_lift_upper_limit}"
effort="${shoulder_lift_effort_limit}" velocity="${shoulder_lift_velocity_limit}"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${shoulder_lift_lower_limit + safety_pos_margin}" soft_upper_limit="${shoulder_lift_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="${tf_prefix}elbow_joint" type="revolute">
<parent link="${tf_prefix}upper_arm_link" />
<child link="${tf_prefix}forearm_link" />
<origin xyz="${forearm_x} ${forearm_y} ${forearm_z}" rpy="${forearm_roll} ${forearm_pitch} ${forearm_yaw}" />
<axis xyz="0 0 1" />
<limit lower="${elbow_joint_lower_limit}" upper="${elbow_joint_upper_limit}"
effort="${elbow_joint_effort_limit}" velocity="${elbow_joint_velocity_limit}"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${elbow_joint_lower_limit + safety_pos_margin}" soft_upper_limit="${elbow_joint_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="${tf_prefix}wrist_1_joint" type="revolute">
<parent link="${tf_prefix}forearm_link" />
<child link="${tf_prefix}wrist_1_link" />
<origin xyz="${wrist_1_x} ${wrist_1_y} ${wrist_1_z}" rpy="${wrist_1_roll} ${wrist_1_pitch} ${wrist_1_yaw}" />
<axis xyz="0 0 1" />
<limit lower="${wrist_1_lower_limit}" upper="${wrist_1_upper_limit}"
effort="${wrist_1_effort_limit}" velocity="${wrist_1_velocity_limit}"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${wrist_1_lower_limit + safety_pos_margin}" soft_upper_limit="${wrist_1_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="${tf_prefix}wrist_2_joint" type="revolute">
<parent link="${tf_prefix}wrist_1_link" />
<child link="${tf_prefix}wrist_2_link" />
<origin xyz="${wrist_2_x} ${wrist_2_y} ${wrist_2_z}" rpy="${wrist_2_roll} ${wrist_2_pitch} ${wrist_2_yaw}" />
<axis xyz="0 0 1" />
<limit lower="${wrist_2_lower_limit}" upper="${wrist_2_upper_limit}"
effort="${wrist_2_effort_limit}" velocity="${wrist_2_velocity_limit}"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${wrist_2_lower_limit + safety_pos_margin}" soft_upper_limit="${wrist_2_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
</joint>
<joint name="${tf_prefix}wrist_3_joint" type="revolute">
<parent link="${tf_prefix}wrist_2_link" />
<child link="${tf_prefix}wrist_3_link" />
<origin xyz="${wrist_3_x} ${wrist_3_y} ${wrist_3_z}" rpy="${wrist_3_roll} ${wrist_3_pitch} ${wrist_3_yaw}" />
<axis xyz="0 0 1" />
<limit lower="${wrist_3_lower_limit}" upper="${wrist_3_upper_limit}"
effort="${wrist_3_effort_limit}" velocity="${wrist_3_velocity_limit}"/>
<xacro:if value="${safety_limits}">
<safety_controller soft_lower_limit="${wrist_3_lower_limit + safety_pos_margin}" soft_upper_limit="${wrist_3_upper_limit - safety_pos_margin}" k_position="${safety_k_position}" k_velocity="0.0"/>
</xacro:if>
<dynamics damping="0" friction="0"/>
</joint>
<link name="${tf_prefix}ft_frame"/>
<joint name="${tf_prefix}wrist_3_link-ft_frame" type="fixed">
<parent link="${tf_prefix}wrist_3_link"/>
<child link="${tf_prefix}ft_frame"/>
<origin xyz="0 0 0" rpy="${pi} 0 0"/>
</joint>
<!-- ROS-Industrial 'base' frame - base_link to UR 'Base' Coordinates transform -->
<link name="${tf_prefix}base"/>
<joint name="${tf_prefix}base_link-base_fixed_joint" type="fixed">
<!-- Note the rotation over Z of pi radians - as base_link is REP-103
aligned (i.e., has X+ forward, Y+ left and Z+ up), this is needed
to correctly align 'base' with the 'Base' coordinate system of
the UR controller.
-->
<origin xyz="0 0 0" rpy="0 0 ${pi}"/>
<parent link="${tf_prefix}base_link"/>
<child link="${tf_prefix}base"/>
</joint>
<!-- ROS-Industrial 'flange' frame - attachment point for EEF models -->
<link name="${tf_prefix}flange" />
<joint name="${tf_prefix}wrist_3-flange" type="fixed">
<parent link="${tf_prefix}wrist_3_link" />
<child link="${tf_prefix}flange" />
<origin xyz="0 0 0" rpy="0 ${-pi/2.0} ${-pi/2.0}" />
</joint>
<!-- ROS-Industrial 'tool0' frame - all-zeros tool frame -->
<link name="${tf_prefix}tool0"/>
<joint name="${tf_prefix}flange-tool0" type="fixed">
<!-- default toolframe - X+ left, Y+ up, Z+ front -->
<origin xyz="0 0 0" rpy="${pi/2.0} 0 ${pi/2.0}"/>
<parent link="${tf_prefix}flange"/>
<child link="${tf_prefix}tool0"/>
</joint>
</xacro:macro>
</robot>