Newer
Older
<?xml version="1.0"?>
<robot name="bluevolta_bravo7_no_ee">
<material name="green">
<color rgba="0.235 0.702 0.443 1"/>
</material>
<material name="blue">
<color rgba="0.263 0.733 0.984 1"/>
</material>
<material name="red">
<color rgba="1 0 0 1"/>
</material>
<material name="black">
<color rgba="0.8 0.8 0.8 1"/>
</material>
<material name="orange">
<color rgba="1 0.369 0.047 1"/>
</material>
<link name="bluevolta_base_link"/>
<joint name="bluevolta_fixed_joint" type="fixed">
<origin xyz="0 0 0" rpy="-3.141592654 0 3.141592654"/>
<parent link="bluevolta_base_link"/>
<child link="bluevolta_rov"/>
</joint>
<link name="bluevolta_rov">
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
<!--Inertial parameters are not correct-->
<inertial>
<mass value="200.0"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.01152" ixy="0.0" ixz="0.0" iyy="0.01152" iyz="0.0" izz="0.0218"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/bluevolta_description/meshes/bluevolta.stl"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/bluevolta_description/meshes/bluevolta_convex_hull.stl"/>
</geometry>
</collision>
</link>
<!--THRUSTERS-->
<link name="Thruster_TOP_FL">
<visual>
<geometry>
<mesh filename="package://example-robot-data/robots/bluevolta_description/meshes/bluevolta_propeller.stl"/>
</geometry>
<material name="red"/>
</visual>
</link>
<link name="Thruster_TOP_FR">
<visual>
<geometry>
<mesh filename="package://example-robot-data/robots/bluevolta_description/meshes/bluevolta_propeller.stl"/>
</geometry>
<material name="red"/>
</visual>
</link>
<link name="Thruster_TOP_B">
<visual>
<geometry>
<mesh filename="package://example-robot-data/robots/bluevolta_description/meshes/bluevolta_propeller.stl"/>
</geometry>
<material name="red"/>
</visual>
</link>
<link name="Thruster_BOTTOM_FL">
<visual>
<geometry>
<mesh filename="package://example-robot-data/robots/bluevolta_description/meshes/bluevolta_propeller.stl"/>
</geometry>
<material name="red"/>
</visual>
</link>
<link name="Thruster_BOTTOM_FR">
<visual>
<geometry>
<mesh filename="package://example-robot-data/robots/bluevolta_description/meshes/bluevolta_propeller.stl"/>
</geometry>
<material name="red"/>
</visual>
</link>
<link name="Thruster_BOTTOM_BL">
<visual>
<geometry>
<mesh filename="package://example-robot-data/robots/bluevolta_description/meshes/bluevolta_propeller.stl"/>
</geometry>
<material name="red"/>
</visual>
</link>
<link name="Thruster_BOTTOM_BR">
<visual>
<geometry>
<mesh filename="package://example-robot-data/robots/bluevolta_description/meshes/bluevolta_propeller.stl"/>
</geometry>
<material name="red"/>
</visual>
</link>
<joint name="Thruster_TOP_FL_joint" type="fixed">
<parent link="bluevolta_rov"/>
<child link="Thruster_TOP_FL"/>
<origin rpy="0.0 1.8 0.0" xyz="0.34 0.25 -0.28"/>
</joint>
<joint name="Thruster_TOP_FR_joint" type="fixed">
<parent link="bluevolta_rov"/>
<child link="Thruster_TOP_FR"/>
<origin rpy="0.0 1.34 0.0" xyz="-0.34 0.25 -0.28"/>
</joint>
<joint name="Thruster_TOP_B_joint" type="fixed">
<parent link="bluevolta_rov"/>
<child link="Thruster_TOP_B"/>
<origin rpy="0.0 1.8 -1.57" xyz="0.0 -0.6 -0.3"/>
</joint>
<joint name="Thruster_BOTTOM_FR_joint" type="fixed">
<parent link="bluevolta_rov"/>
<child link="Thruster_BOTTOM_FR"/>
<origin rpy="0.0 0.0 -2.24" xyz="-0.31 0.52 -0.1"/>
</joint>
<joint name="Thruster_BOTTOM_BL_joint" type="fixed">
<parent link="bluevolta_rov"/>
<child link="Thruster_BOTTOM_BL"/>
<origin rpy="0.0 0.0 -2.24" xyz="0.27 -0.6 -0.11"/>
</joint>
<joint name="Thruster_BOTTOM_FL_joint" type="fixed">
<parent link="bluevolta_rov"/>
<child link="Thruster_BOTTOM_FL"/>
<origin rpy="0.0 0.0 -0.9" xyz="0.31 0.52 -0.1"/>
</joint>
<joint name="Thruster_BOTTOM_BR_joint" type="fixed">
<parent link="bluevolta_rov"/>
<child link="Thruster_BOTTOM_BR"/>
<origin rpy="0.0 0.0 -0.9" xyz="-0.27 -0.6 -0.11"/>
</joint>
<!--Arm attaching link-->
<link name="box_base_bravo">
<visual>
<geometry>
<box size="0.1 0.1 0.1"/>
</geometry>
<material name="orange"/>
</visual>
</link>
<joint name="box_base_bravo_joint" type="fixed">
<origin xyz="-0.25 0.835 0.17" rpy="0 0 0"/>
<parent link="bluevolta_rov"/>
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
<child link="box_base_bravo"/>
</joint>
<joint name="base2arm" type="fixed">
<parent link="box_base_bravo"/>
<child link="link1"/>
<origin rpy="3.14 0.0 1.57" xyz="0 -0.05 -0.05"/>
</joint>
<!-- Bravo7 with sphere end-effector -->
<link name="link1">
<visual>
<geometry>
<mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-266.stl"/>
</geometry>
<material name="blue"/>
</visual>
<inertial>
<mass value="1.25"/>
<origin xyz="-0.075 -0.006 -0.003"/>
<inertia ixx="0.002108" ixy="0.000182" ixz="-0.000015" iyy="0.002573" iyz="-0.000021" izz="0.003483"/>
</inertial>
<collision>
<geometry>
<mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-266_convex_hull.stl"/>
</geometry>
</collision>
</link>
<joint name="joint1" type="continuous">
<parent link="link1"/>
<child link="link2"/>
<origin rpy="3.141592654 0 0" xyz="0.0665 0 0.078"/>
<axis xyz="0 0 1"/>
</joint>
<link name="link2">
<visual>
<origin xyz="0 0 0" rpy="-3.141592654 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-217.stl"/>
</geometry>
<material name="green"/>
</visual>
<inertial>
<mass value="1.55" />
<inertia ixx="0.011442" ixy="-0.000484" ixz="0.003405" iyy="0.01298" iyz="-0.001265" izz="0.003202"/>
<origin xyz="0.005 -0.001 0.016" rpy="-3.141592654 0 0"/>
<origin xyz="0 0 0" rpy="-3.141592654 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-217_convex_hull.stl"/>
</geometry>
</collision>
</link>
<joint name="joint2" type="revolute">
<parent link="link2"/>
<child link="link3"/>
<origin rpy="3.141592654 0 0" xyz="-0.046 0 -0.0674"/>
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
<axis xyz="0 1 0"/>
<limit effort="9.0" lower="0.0" upper="3.5" velocity="0.5"/>
</joint>
<link name="link3">
<visual>
<geometry>
<mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-250-212-214.stl"/>
</geometry>
<material name="blue"/>
</visual>
<inertial>
<mass value="1.14" />
<origin xyz="0.022 -0.029 0.001" />
<inertia ixx="0.003213" ixy="-0.001548" ixz="-0.000031" iyy="0.002327" iyz="0.000006" izz="0.00434"/>
</inertial>
<collision>
<geometry>
<mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-250-212-214_convex_hull.stl"/>
</geometry>
</collision>
</link>
<joint name="joint3" type="revolute">
<parent link="link3"/>
<child link="link4"/>
<origin rpy="0 0 0" xyz="-0.0052 0 -0.29055"/>
<axis xyz="0 1 0"/>
<limit effort="9.0" lower="0.0" upper="3.5" velocity="0.5"/>
</joint>
<link name="link4">
<visual>
<geometry>
<mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-268.stl"/>
</geometry>
<material name="green"/>
</visual>
<collision>
<geometry>
<mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-268_convex_hull.stl"/>
</geometry>
<material name="green"/>
</collision>
<inertial>
<origin xyz="0.017 -0.026 -0.002" rpy="0.0 -0.0 0.0" />
<mass value="1.14" />
<inertia ixx="0.021232" ixy="0.00033" ixz="-0.003738" iyy="0.022252" iyz="-0.001278" izz="0.002054"/>
</inertial>
</link>
<joint name="joint4" type="continuous">
<parent link="link4"/>
<child link="link5"/>
<origin rpy="3.141592654 0 0" xyz="0.0408 0 0.09695"/>
<axis xyz="0 0 1"/>
</joint>
<link name="link5">
<visual>
<origin xyz="0 0 0" rpy="-3.141592654 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-214.stl"/>
</geometry>
<material name="blue"/>
</visual>
<inertial>
<mass value="1.03" />
<origin xyz="0.020 -0.024 0.001" rpy="-3.141592654 0 0"/>
<inertia ixx="0.00243" ixy="-0.001144" ixz="-0.00004" iyy="0.002026" iyz="0.000011" izz="0.00333"/>
<origin xyz="0 0 0" rpy="-3.141592654 0 0"/>
<geometry>
<mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-214_convex_hull.stl"/>
</geometry>
</collision>
</link>
<joint name="joint5" type="revolute">
<parent link="link5"/>
<child link="link6"/>
<origin rpy="3.141592654 0 0" xyz="-0.0408 0 -0.063"/>
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
<axis xyz="0 1 0"/>
<limit effort="9.0" lower="0.0" upper="3.5" velocity="0.5"/>
</joint>
<link name="link6">
<visual>
<geometry>
<mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-161.stl"/>
</geometry>
<material name="green"/>
</visual>
<inertial>
<origin xyz="0.0 0.003 -0.098" rpy="0.0 -0.0 0.0" />
<mass value="0.333" />
<inertia ixx="0.003709" ixy="-0.000002" ixz="-0.000004" iyy="0.003734" iyz="0.0" izz="0.000079" />
</inertial>
<collision>
<geometry>
<mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-161_convex_hull.stl"/>
</geometry>
</collision>
</link>
<joint name="joint6" type="continuous">
<parent link="link6"/>
<child link="link7"/>
<origin rpy="0 3.14159 0" xyz="-0.0408 0 -0.14863"/>
<axis xyz="0 0 1"/>
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
</joint>
<link name="link7">
<visual>
<geometry>
<mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-180.stl"/>
</geometry>
<material name="blue"/>
</visual>
<inertial>
<origin xyz="0.0 0.003 -0.098" />
<mass value="1.04" />
<inertia ixx="0.022359" ixy="0.000001" ixz="-0.000019" iyy="0.022363" iyz="0.000015" izz="0.000936"/>
</inertial>
<collision>
<geometry>
<mesh filename="package://example-robot-data/robots/bravo7_description/meshes/RS2-180_convex_hull.stl"/>
</geometry>
</collision>
</link>
<link name="force_torque_sensor">
<visual>
<geometry>
<cylinder length="0.06" radius="0.04"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<geometry>
<cylinder length="0.06" radius="0.04"/>
</geometry>
<material name="orange"/>
</collision>
</link>
<joint name="FT_fixed_1" type="fixed">
<origin rpy="0 0 1.57" xyz=" 0 0 -0.03"/>
<parent link="link7"/>
<child link="force_torque_sensor"/>
</joint>
<link name="end_effector_ball">
<visual>
<geometry>
<mesh filename="package://example-robot-data/robots/bravo7_description/meshes/end_effectors/contact_sphere.stl"/>
</geometry>
<material name="red"/>
</visual>
<collision>
<geometry>
<mesh filename="package://example-robot-data/robots/bravo7_description/meshes/end_effectors/contact_sphere_convex_hull.stl"/>
</geometry>
<material name="red"/>
</collision>
</link>
<joint name="bravo_EE_joint" type="fixed">
<origin rpy="0 -1.57 0" xyz=" 0.045 -0.035 0.113"/>
<parent link="link7"/>
<child link="end_effector_ball"/>
</joint>
<link name="contact_point"/>
<joint name="contact_point_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.24"/>
<parent link="force_torque_sensor"/>
<child link="contact_point"/>
</joint>
</robot>