Newer
Older
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
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find ur_description)/urdf/ur10.transmission.xacro" />
<xacro:include filename="$(find ur_description)/urdf/ur10.gazebo.xacro" />
<xacro:include filename="$(find ur_description)/urdf/materials.urdf.xacro" />
<property name="pi" value="3.14159265" />
<!-- Inertia parameters -->
<property name="base_mass" value="4.0" />
<property name="shoulder_mass" value="3.7000" />
<property name="upper_arm_mass" value="8.3930" />
<property name="forearm_mass" value="2.2750" />
<property name="wrist_1_mass" value="1.2190" />
<property name="wrist_2_mass" value="1.2190" />
<property name="wrist_3_mass" value="0.1879" />
<property name="shoulder_cog" value="0.0 0.00193 -0.02561" />
<property name="upper_arm_cog" value="0.0 -0.024201 0.2125" />
<property name="forearm_cog" value="0.0 0.0265 0.11993" />
<property name="wrist_1_cog" value="0.0 0.110949 0.01634" />
<property name="wrist_2_cog" value="0.0 0.0018 0.11099" />
<property name="wrist_3_cog" value="0.0 0.001159 0.0" />
<!-- Kinematic model -->
<property name="shoulder_height" value="0.128" />
<property name="shoulder_offset" value="0.1704" />
<property name="upper_arm_length" value="0.60186" />
<property name="elbow_offset" value="0.12817" />
<property name="forearm_length" value="0.56415" />
<property name="wrist_1_length" value="0.11279" />
<property name="wrist_2_length" value="0.11279" />
<property name="wrist_3_length" value="0.0857" />
<property name="shoulder_radius" value="0.060" />
<property name="upper_arm_radius" value="0.054" />
<property name="elbow_radius" value="0.060" />
<property name="forearm_radius" value="0.040" />
<property name="wrist_radius" value="0.045" />
<!-- Collision model -->
<property name="base_collision_length" value="0.160" />
<property name="shoulder_collision_length" value="0.200" />
<property name="shoulder_collision_offset" value="0.035" />
<property name="elbow_collision_length" value="0.200" />
<property name="elbow_collision_offset" value="0.035" />
<xacro:macro name="ur10_robot" params="prefix">
<link name="${prefix}base_link" >
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/visual/Base.stl" />
</geometry>
<origin xyz="0.0 0.0 0.003" rpy="0.0 0.0 ${3.0 * pi / 4.0}" />
<material name="UR/Blue" />
</visual>
<collision>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/collision/Base.stl" />
</geometry>
<origin xyz="0.0 0.0 0.003" rpy="0.0 0.0 ${3.0 * pi / 4.0}" />
</collision>
<inertial>
<mass value="${base_mass}" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
<joint name="${prefix}shoulder_pan_joint" type="revolute">
<parent link="${prefix}base_link" />
<child link = "${prefix}shoulder_link" />
<origin xyz="0.0 0.0 ${shoulder_height}" rpy="0.0 0.0 0.0" />
<axis xyz="0.0 0.0 1.0" />
<limit lower="${-pi}" upper="${pi}" effort="330.0" velocity="2.16"/>
<dynamics damping="1.2" friction="0.0"/>
</joint>
<link name="${prefix}shoulder_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/visual/Shoulder.stl" />
</geometry>
<material name="UR/Grey" />
</visual>
<collision>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/collision/Shoulder.stl" />
</geometry>
</collision>
<inertial>
<mass value="${shoulder_mass}" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
<origin xyz="${shoulder_cog}" rpy="0.0 0.0 0.0" />
</inertial>
</link>
<joint name="${prefix}shoulder_lift_joint" type="revolute">
<parent link="${prefix}shoulder_link" />
<child link = "${prefix}upper_arm_link" />
<origin xyz="0.0 ${shoulder_offset} 0.0" rpy="0.0 ${pi / 2.0} 0.0" />
<axis xyz="0.0 1.0 0.0" />
<limit lower="${-pi}" upper="${pi}" effort="10.0" velocity="${pi}"/>
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
<dynamics damping="1.2" friction="0.0"/>
</joint>
<link name="${prefix}upper_arm_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/visual/UpperArm.stl" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
<material name="UR/Blue" />
</visual>
<collision>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/collision/UpperArm.stl" />
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
</collision>
<inertial>
<mass value="${upper_arm_mass}" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
<origin xyz="${upper_arm_cog}" rpy="0.0 0.0 0.0" />
</inertial>
</link>
<joint name="${prefix}elbow_joint" type="revolute">
<parent link="${prefix}upper_arm_link" />
<child link = "${prefix}forearm_link" />
<origin xyz="0.0 ${-elbow_offset} ${upper_arm_length}" rpy="0.0 0.0 0.0" />
<axis xyz="0.0 1.0 0.0" />
<limit lower="${-pi}" upper="${pi}" effort="150.0" velocity="${pi}"/>
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
<dynamics damping="0.6" friction="0.0"/>
</joint>
<link name="${prefix}forearm_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/visual/Forearm.stl" />
</geometry>
<material name="UR/Grey" />
</visual>
<collision>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/collision/Forearm.stl" />
</geometry>
</collision>
<inertial>
<mass value="${forearm_mass}" />
<origin xyz="${forearm_cog}" rpy="0.0 0.0 0.0" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
<joint name="${prefix}wrist_1_joint" type="revolute">
<parent link="${prefix}forearm_link" />
<child link = "${prefix}wrist_1_link" />
<origin xyz="0.0 0.0 ${forearm_length}" rpy="0.0 ${pi / 2.0} 0.0" />
<axis xyz="0.0 1.0 0.0" />
<limit lower="${-pi}" upper="${pi}" effort="54.0" velocity="${pi}"/>
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
<dynamics damping="0.6" friction="0.0"/>
</joint>
<link name="${prefix}wrist_1_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/visual/Wrist1.stl" />
</geometry>
<origin xyz="0.0 ${wrist_1_length} 0.0" rpy="0.0 0 0.0" />
<material name="UR/Blue" />
</visual>
<collision>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/collision/Wrist1.stl" />
</geometry>
<origin xyz="0.0 ${wrist_1_length} 0.0" rpy="0.0 0 0.0" />
</collision>
<inertial>
<mass value="${wrist_1_mass}" />
<origin xyz="${wrist_1_cog}" rpy="0.0 0.0 0.0" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
<joint name="${prefix}wrist_2_joint" type="revolute">
<parent link="${prefix}wrist_1_link" />
<child link = "${prefix}wrist_2_link" />
<origin xyz="0.0 ${wrist_1_length} 0.0" rpy="0.0 0.0 0.0" />
<axis xyz="0.0 0.0 1.0" />
<limit lower="${-pi}" upper="${pi}" effort="54.0" velocity="${pi}"/>
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
<dynamics damping="0.6" friction="0.0"/>
</joint>
<link name="${prefix}wrist_2_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/visual/Wrist2.stl" />
</geometry>
<origin xyz="0.0 0.0 ${wrist_2_length}" rpy="0.0 0.0 0.0" />
<material name="UR/Grey" />
</visual>
<collision>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/collision/Wrist2.stl" />
</geometry>
<origin xyz="0.0 0.0 ${wrist_2_length}" rpy="0.0 0.0 0.0" />
</collision>
<inertial>
<mass value="${wrist_2_mass}" />
<origin xyz="${wrist_2_cog}" rpy="0.0 0.0 0.0" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
<joint name="${prefix}wrist_3_joint" type="revolute">
<parent link="${prefix}wrist_2_link" />
<child link = "${prefix}wrist_3_link" />
<origin xyz="0.0 0.0 ${wrist_2_length}" rpy="0.0 0.0 0.0" />
<axis xyz="0.0 1.0 0.0" />
<limit lower="${-pi}" upper="${pi}" effort="54.0" velocity="${pi}"/>
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
<dynamics damping="0.6" friction="0.0"/>
</joint>
<link name="${prefix}wrist_3_link">
<visual>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/visual/Wrist3.stl" />
</geometry>
<origin xyz="0.0 ${wrist_3_length} 0.0" rpy="0.0 0.0 0" />
<material name="UR/Blue" />
</visual>
<collision>
<geometry>
<mesh filename="package://ur_description/meshes/ur10/collision/Wrist3.stl" />
</geometry>
<origin xyz="0.0 ${wrist_3_length} 0.0" rpy="0.0 0.0 0" />
</collision>
<inertial>
<mass value="${wrist_3_mass}" />
<origin xyz="${wrist_3_cog}" rpy="0.0 0.0 0.0" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
</inertial>
</link>
<joint name="${prefix}ee_fixed_joint" type="fixed">
<parent link="${prefix}wrist_3_link" />
<child link = "${prefix}ee_link" />
<origin xyz="0.0 ${wrist_3_length} 0.0" rpy="0.0 0.0 ${pi/2.0}" />
</joint>
<link name="${prefix}ee_link" />
<xacro:ur10_arm_transmission prefix="${prefix}" />
<xacro:ur10_arm_gazebo prefix="${prefix}" />
</xacro:macro>
</robot>