bolt.urdf 15.2 KB
Newer Older
Julian Viereck's avatar
Merge  
Julian Viereck committed
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
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- |    This document was autogenerated by xacro from /usr/local/lib/python3.9/site-packages/robot_properties_bolt/resources/xacro/bolt.urdf.xacro | -->
<!-- |    EDITING THIS FILE BY HAND IS NOT RECOMMENDED                                 | -->
<!-- =================================================================================== -->
<robot name="bolt" xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor" xmlns:xacro="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface">
  <!-- This file is based on: https://atlas.is.localnet/confluence/display/AMDW/Quadruped+URDF+Files -->
  <link name="base_link">
    <!-- BASE LINK INERTIAL -->
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="0.61436936"/>
      <!-- The base is extremely symmetrical. -->
      <inertia ixx="0.00578574" ixy="0.0" ixz="0.0" iyy="0.01938108" iyz="0.0" izz="0.02476124"/>
    </inertial>
    <!-- BASE LINK VISUAL -->
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://example-robot-data/robots/bolt/meshes/stl/bolt_body.stl"/>
      </geometry>
      <material name="grey">
        <color rgba="0.8 0.8 0.8 1.0"/>
      </material>
    </visual>
    <!-- BASE LINK COLLISION -->
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://example-robot-data/robots/bolt/meshes/stl/bolt_body.stl"/>
      </geometry>
      <material name="grey">
        <color rgba="0.8 0.8 0.8 1.0"/>
      </material>
    </collision>
    <!-- Bullet specific paramters -->
    <contact>
      <lateral_friction value="1.0"/>
      <restitution value="0.5"/>
    </contact>
  </link>
  <!-- END BASE LINK -->
  <!--xacro:property name="base_2_HAA_x" value="${2.45656 * 0.001}" />
  <xacro:property name="base_2_HAA_y" value="${63.6 * 0.001}" />
  <xacro:property name="base_2_HAA_z" value="${33.0809 * 0.001}" /-->
  <joint name="FL_HAA" type="revolute">
    <parent link="base_link"/>
    <child link="FL_SHOULDER"/>
    <limit effort="1000" lower="-10" upper="10" velocity="1000"/>
    <!-- joints rotates around the x-axis -->
    <axis xyz="1 0 0"/>
    <origin rpy="0 0 0" xyz="0.0 0.0636 0"/>
    <!--xacro:unless value="${is_right}">
        <origin xyz="${base_2_HAA_x} ${base_2_HAA_y + 0.0007888} ${-base_2_HAA_z}" rpy="0 0 0" />
      </xacro:unless>
      <xacro:if value="${is_right}">
        <origin xyz="${base_2_HAA_x} ${-base_2_HAA_y + 0.0007888} ${-base_2_HAA_z}" rpy="0 0 0" />
      </xacro:if-->
    <!-- pybullet simulation parameters -->
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="FL_SHOULDER">
    <!-- TODO: Update inertias and add visuals for link. -->
    <!-- create a dummy shoulder link to join the two joints -->
    <inertial>
      <!-- Left upper leg inertia -->
      <mass value="0.14004265"/>
      <origin rpy="0 0 0" xyz="0.01708256 -0.00446892 -0.01095830"/>
      <inertia ixx="0.00007443" ixy="0.00000148" ixz="0.00002154" iyy="0.00013847" iyz="-0.00001096" izz="0.00009002"/>
    </inertial>
    <!-- HIP LEG LINK VISUAL -->
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://example-robot-data/robots/bolt/meshes/stl/bolt_hip_fe_left_side.stl"/>
      </geometry>
      <material name="grey">
        <color rgba="0.8 0.8 0.8 1.0"/>
      </material>
    </visual>
    <!-- UPPER LEG LINK COLLISION -->
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://example-robot-data/robots/bolt/meshes/stl/bolt_hip_fe_left_side.stl"/>
      </geometry>
      <material name="grey">
        <color rgba="0.8 0.8 0.8 1.0"/>
      </material>
    </collision>
    <!-- Bullet specific paramters -->
    <contact>
      <lateral_friction value="1.0"/>
      <restitution value="0.5"/>
    </contact>
  </link>
  <joint name="FL_HFE" type="revolute">
    <parent link="FL_SHOULDER"/>
    <child link="FL_UPPER_LEG"/>
    <limit effort="1000" lower="-10" upper="10" velocity="1000"/>
    <!-- joints rotates around the y-axis -->
    <axis xyz="0 1 0"/>
    <origin rpy="0 0 0" xyz="0 0.0145 -0.0386"/>
    <!-- pybullet simulation parameters -->
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="FL_UPPER_LEG">
    <!-- Left upper leg inertia -->
    <inertial>
      <origin rpy="0 0 0" xyz="0.00001377 0.01935853 -0.11870700"/>
      <mass value="0.14853845"/>
      <inertia ixx="0.00041107" ixy="0.00000000" ixz="0.00000009" iyy="0.00041193" iyz="-0.00004671" izz="0.00003024"/>
    </inertial>
    <!-- UPPER LEG LINK VISUAL -->
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://example-robot-data/robots/bolt/meshes/stl/upper_leg_200mm_left_side.stl"/>
      </geometry>
      <material name="grey">
        <color rgba="0.8 0.8 0.8 1.0"/>
      </material>
    </visual>
    <!-- UPPER LEG LINK COLLISION -->
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://example-robot-data/robots/bolt/meshes/stl/upper_leg_200mm_left_side.stl"/>
      </geometry>
      <material name="grey">
        <color rgba="0.8 0.8 0.8 1.0"/>
      </material>
    </collision>
    <!-- Bullet specific paramters -->
    <contact>
      <lateral_friction value="1.0"/>
      <restitution value="0.5"/>
    </contact>
  </link>
  <!-- END UPPER LEG LINK -->
  <!-- KFE: Joint between the upper leg and the lower leg -->
  <joint name="FL_KFE" type="revolute">
    <parent link="FL_UPPER_LEG"/>
    <child link="FL_LOWER_LEG"/>
    <limit effort="1000" lower="-10" upper="10" velocity="1000"/>
    <!-- joints rotates around the y-axis -->
    <axis xyz="0 1 0"/>
    <origin rpy="0 0 0" xyz="0 0.0374 -0.2"/>
    <!-- pybullet simulation parameters -->
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="FL_LOWER_LEG">
    <!-- Left lower leg inertia -->
    <inertial>
      <origin rpy="0 0 0" xyz="0.0 0.00836718 -0.11591877"/>
      <mass value="0.03117243"/>
      <inertia ixx="0.00011487" ixy="0.00000000" ixz="0.00000000" iyy="0.00011556" iyz="-0.00000190" izz="0.00000220"/>
    </inertial>
    <!-- LOWER LEG LINK VISUAL -->
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://example-robot-data/robots/bolt/meshes/stl/lower_leg_200mm_left_side.stl"/>
      </geometry>
      <material name="grey">
        <color rgba="0.8 0.8 0.8 1.0"/>
      </material>
    </visual>
    <!-- LOWER LEG LINK COLLISION -->
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://example-robot-data/robots/bolt/meshes/stl/lower_leg_200mm_left_side.stl"/>
      </geometry>
      <material name="grey">
        <color rgba="0.8 0.8 0.8 1.0"/>
      </material>
    </collision>
    <!-- Bullet specific paramters -->
    <contact>
      <lateral_friction value="1.0"/>
      <restitution value="0.5"/>
    </contact>
  </link>
  <!-- END LOWER LEG LINK -->
  <!-- KFE: Joint between the upper leg and the lower leg -->
  <joint name="FL_ANKLE" type="fixed">
    <parent link="FL_LOWER_LEG"/>
    <child link="FL_FOOT"/>
    <origin rpy="0 0 0" xyz="0 0.008 -0.2"/>
    <!-- Limits (usefull?) -->
    <limit effort="1000" lower="-10" upper="10" velocity="1000"/>
    <!-- pybullet simulation parameters -->
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="FL_FOOT">
    <!-- FOOT INERTIAL -->
    <!-- This link is symmetrical left or right -->
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0.00035767"/>
      <mass value="0.00000000"/>
      <inertia ixx="0.00000057" ixy="0.0" ixz="0.0" iyy="0.00000084" iyz="0.0" izz="0.00000053"/>
    </inertial>
    <!-- FOOT VISUAL -->
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://example-robot-data/robots/bolt/meshes/stl/bolt_foot.stl"/>
      </geometry>
      <material name="grey">
        <color rgba="0.8 0.8 0.8 1.0"/>
      </material>
    </visual>
    <!-- FOOT COLLISION -->
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://example-robot-data/robots/bolt/meshes/stl/bolt_foot.stl"/>
      </geometry>
      <material name="grey">
        <color rgba="0.8 0.8 0.8 1.0"/>
      </material>
    </collision>
    <!-- Bullet specific paramters -->
    <contact>
      <lateral_friction value="4.0"/>
      <restitution value="0.0"/>
    </contact>
  </link>
  <!-- END LOWER LEG LINK -->
  <joint name="FR_HAA" type="revolute">
    <parent link="base_link"/>
    <child link="FR_SHOULDER"/>
    <limit effort="1000" lower="-10" upper="10" velocity="1000"/>
    <!-- joints rotates around the x-axis -->
    <axis xyz="1 0 0"/>
    <origin rpy="0 0 0" xyz="0.0 -0.0636 0"/>
    <!--xacro:unless value="${is_right}">
        <origin xyz="${base_2_HAA_x} ${base_2_HAA_y + 0.0007888} ${-base_2_HAA_z}" rpy="0 0 0" />
      </xacro:unless>
      <xacro:if value="${is_right}">
        <origin xyz="${base_2_HAA_x} ${-base_2_HAA_y + 0.0007888} ${-base_2_HAA_z}" rpy="0 0 0" />
      </xacro:if-->
    <!-- pybullet simulation parameters -->
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="FR_SHOULDER">
    <!-- TODO: Update inertias and add visuals for link. -->
    <!-- create a dummy shoulder link to join the two joints -->
    <inertial>
      <!-- Right upper leg inertia -->
      <mass value="0.14004412"/>
      <origin rpy="0 0 0" xyz="0.01708233 0.00447099 -0.01095846"/>
      <inertia ixx="0.00007442" ixy="-0.00000148" ixz="0.00002154" iyy="0.00013848" iyz="0.00001095" izz="0.00009001"/>
    </inertial>
    <!-- HIP LEG LINK VISUAL -->
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://example-robot-data/robots/bolt/meshes/stl/bolt_hip_fe_right_side.stl"/>
      </geometry>
      <material name="grey">
        <color rgba="0.8 0.8 0.8 1.0"/>
      </material>
    </visual>
    <!-- UPPER LEG LINK COLLISION -->
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://example-robot-data/robots/bolt/meshes/stl/bolt_hip_fe_right_side.stl"/>
      </geometry>
      <material name="grey">
        <color rgba="0.8 0.8 0.8 1.0"/>
      </material>
    </collision>
    <!-- Bullet specific paramters -->
    <contact>
      <lateral_friction value="1.0"/>
      <restitution value="0.5"/>
    </contact>
  </link>
  <joint name="FR_HFE" type="revolute">
    <parent link="FR_SHOULDER"/>
    <child link="FR_UPPER_LEG"/>
    <limit effort="1000" lower="-10" upper="10" velocity="1000"/>
    <!-- joints rotates around the y-axis -->
    <axis xyz="0 1 0"/>
    <origin rpy="0 0 0" xyz="0 -0.0145 -0.0386"/>
    <!-- pybullet simulation parameters -->
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="FR_UPPER_LEG">
    <!-- Right upper leg inertia -->
    <inertial>
      <origin rpy="0 0 0" xyz="-0.00001377 -0.01935853 -0.11870700"/>
      <mass value="0.14853845"/>
      <inertia ixx="0.00041107" ixy="0.00000000" ixz="-0.00000009" iyy="0.00041193" iyz="0.00004671" izz="0.00003024"/>
    </inertial>
    <!-- UPPER LEG LINK VISUAL -->
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://example-robot-data/robots/bolt/meshes/stl/upper_leg_200mm_right_side.stl"/>
      </geometry>
      <material name="grey">
        <color rgba="0.8 0.8 0.8 1.0"/>
      </material>
    </visual>
    <!-- UPPER LEG LINK COLLISION -->
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://example-robot-data/robots/bolt/meshes/stl/upper_leg_200mm_right_side.stl"/>
      </geometry>
      <material name="grey">
        <color rgba="0.8 0.8 0.8 1.0"/>
      </material>
    </collision>
    <!-- Bullet specific paramters -->
    <contact>
      <lateral_friction value="1.0"/>
      <restitution value="0.5"/>
    </contact>
  </link>
  <!-- END UPPER LEG LINK -->
  <!-- KFE: Joint between the upper leg and the lower leg -->
  <joint name="FR_KFE" type="revolute">
    <parent link="FR_UPPER_LEG"/>
    <child link="FR_LOWER_LEG"/>
    <limit effort="1000" lower="-10" upper="10" velocity="1000"/>
    <!-- joints rotates around the y-axis -->
    <axis xyz="0 1 0"/>
    <origin rpy="0 0 0" xyz="0 -0.0374 -0.2"/>
    <!-- pybullet simulation parameters -->
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="FR_LOWER_LEG">
    <!-- Right lower leg inertia -->
    <inertial>
      <origin rpy="0 0 0" xyz="0.0 -0.00836718 -0.11591877"/>
      <mass value="0.03117243"/>
      <inertia ixx="0.00011487" ixy="0.00000000" ixz="0.00000000" iyy="0.00011556" iyz="0.00000190" izz="0.00000220"/>
    </inertial>
    <!-- LOWER LEG LINK VISUAL -->
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://example-robot-data/robots/bolt/meshes/stl/lower_leg_200mm_right_side.stl"/>
      </geometry>
      <material name="grey">
        <color rgba="0.8 0.8 0.8 1.0"/>
      </material>
    </visual>
    <!-- LOWER LEG LINK COLLISION -->
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://example-robot-data/robots/bolt/meshes/stl/lower_leg_200mm_right_side.stl"/>
      </geometry>
      <material name="grey">
        <color rgba="0.8 0.8 0.8 1.0"/>
      </material>
    </collision>
    <!-- Bullet specific paramters -->
    <contact>
      <lateral_friction value="1.0"/>
      <restitution value="0.5"/>
    </contact>
  </link>
  <!-- END LOWER LEG LINK -->
  <!-- KFE: Joint between the upper leg and the lower leg -->
  <joint name="FR_ANKLE" type="fixed">
    <parent link="FR_LOWER_LEG"/>
    <child link="FR_FOOT"/>
    <origin rpy="0 0 0" xyz="0 -0.008 -0.2"/>
    <!-- Limits (usefull?) -->
    <limit effort="1000" lower="-10" upper="10" velocity="1000"/>
    <!-- pybullet simulation parameters -->
    <dynamics damping="0.0" friction="0.0"/>
  </joint>
  <link name="FR_FOOT">
    <!-- FOOT INERTIAL -->
    <!-- This link is symmetrical left or right -->
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0.00035767"/>
      <mass value="0.00000000"/>
      <inertia ixx="0.00000057" ixy="0.0" ixz="0.0" iyy="0.00000084" iyz="0.0" izz="0.00000053"/>
    </inertial>
    <!-- FOOT VISUAL -->
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://example-robot-data/robots/bolt/meshes/stl/bolt_foot.stl"/>
      </geometry>
      <material name="grey">
        <color rgba="0.8 0.8 0.8 1.0"/>
      </material>
    </visual>
    <!-- FOOT COLLISION -->
    <collision>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="package://example-robot-data/robots/bolt/meshes/stl/bolt_foot.stl"/>
      </geometry>
      <material name="grey">
        <color rgba="0.8 0.8 0.8 1.0"/>
      </material>
    </collision>
    <!-- Bullet specific paramters -->
    <contact>
      <lateral_friction value="4.0"/>
      <restitution value="0.0"/>
    </contact>
  </link>
  <!-- END LOWER LEG LINK -->
</robot>