-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathmarimba.urdf.xacro
421 lines (361 loc) · 24.8 KB
/
marimba.urdf.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
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
<?xml version="1.0" ?>
<robot name="marimba" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:arg name="bars_fixed_joint" default="true" />
<xacro:include filename="$(find marimbabot_description)/urdf/utilities.xacro" />
<xacro:include filename="$(find marimbabot_description)/urdf/materials.xacro" />
<!-- URDF/Gazebo model of a marimba.
Coordinate system:
From the point of view of the marimbist:
x: points towards you
y: points towards the right
z: points towards the ceiling, according to right hand rule
Changelog:
2023.01.04 First version created
2023.01.19 Row of keys working
2023.01.26 Complete model v1
2023.03.02 Named and correctly positioned bar frames
Added side boxes
2023.06.14 Made side boxed width and height smaller
-->
<!-- Number of bars (including "missing" ones in the top row) -->
<xacro:property name="n_bars_bottom" value="22" />
<xacro:property name="n_bars_top" value="20" />
<!-- Bar dimensions -->
<xacro:property name="bar_width" value="0.0323" />
<xacro:property name="bar_height" value="0.0185" />
<xacro:property name="bar_length_bottom_left" value="0.32" />
<xacro:property name="bar_length_bottom_right" value="0.173" />
<xacro:property name="bar_length_top_left" value="0.314" />
<xacro:property name="bar_length_top_right" value="0.185" />
<!-- Gap between 2 consecutive bars -->
<xacro:property name="bar_gap" value="0.0075" />
<!-- Body bottom pos & dimensions -->
<xacro:property name="body_bottom_pos" value="0 0 0" />
<xacro:property name="body_bottom_rpy" value="0 0 0.18" />
<xacro:property name="body_bottom_length" value="0.82" />
<xacro:property name="body_bottom_width" value="0.2" />
<xacro:property name="body_bottom_height" value="0.03" />
<xacro:property name="body_bottom_slope" value="-0.35" />
<!-- Displacement between top and bottom rows
x: between the long axes
y: shift along long axis
z: height
-->
<xacro:property name="body_top_bottom_disp_x" value="-0.18" />
<xacro:property name="body_top_bottom_disp_y" value="-0.02" />
<xacro:property name="body_top_bottom_disp_z" value="${0.0149 + bar_height}" />
<!-- Body top pos & dimensions -->
<xacro:property name="body_top_pos" value="
${float(body_bottom_pos.split()[0]) + body_top_bottom_disp_x}
${float(body_bottom_pos.split()[1]) + body_top_bottom_disp_y}
${float(body_bottom_pos.split()[2]) + body_top_bottom_disp_z}"
/>
<xacro:property name="body_top_rpy" value="0 0 -0.15" />
<xacro:property name="body_top_length" value="0.75" />
<xacro:property name="body_top_width" value="0.12" />
<xacro:property name="body_top_height" value="0.03" />
<xacro:property name="body_top_slope" value="-0.12" />
<!-- Bottom row of bars starting pos (center of leftmost bar) -->
<xacro:property name="bottom_left_offset" value="0.05" />
<xacro:property name="bottom_left_center_x" value="${float(body_bottom_pos.split()[0]) + bottom_left_offset}" />
<xacro:property name="bottom_left_center_y" value="${float(body_bottom_pos.split()[1]) - body_bottom_length / 2}" />
<xacro:property name="bottom_left_center_z" value="${float(body_bottom_pos.split()[1]) + body_bottom_height / 2 + bar_height}" />
<!-- Top row of bars starting pos (center of leftmost bar) -->
<xacro:property name="top_left_offset" value="-0.03" />
<xacro:property name="top_left_center_x" value="${float(body_top_pos.split()[0]) + top_left_offset}" />
<xacro:property name="top_left_center_y" value="${float(body_top_pos.split()[1]) - body_top_length / 2}" />
<xacro:property name="top_left_center_z" value="${float(body_top_pos.split()[2]) + body_top_height / 2 + bar_height}" />
<!-- Side boxes (left being the longer side) -->
<xacro:property name="side_width" value="0.028" />
<xacro:property name="side_length_left" value="0.61" />
<xacro:property name="side_length_right" value="0.32" />
<xacro:property name="side_height" value="0.07" /> <!-- 0.07 on the high side, 0.041 on the low side.
The low side starts at 0.28 when counting from the high side.
This is not taken into account here. -->
<xacro:property name="side_offset" value="0.058" />
<xacro:property name="side_left_pos" value="
${(top_left_center_x + bottom_left_center_x) / 2}
${top_left_center_y - side_offset}
${bottom_left_center_z}"
/>
<xacro:property name="side_right_pos" value="
${float(side_left_pos.split()[0])}
${float(side_left_pos.split()[1]) + n_bars_bottom * (bar_width + bar_gap) - 1.5 * bar_gap + side_offset}
${float(side_left_pos.split()[2])}"
/>
<!-- The bar -->
<xacro:macro name="bar" params="note parent id pos length add_low_frame:=0" >
<gazebo reference="bar_${note}" >
<turnGravityOff>false</turnGravityOff>
<selfCollide>true</selfCollide>
<!-- TODO material -->
<!-- <material>chordophones/OakWood</material> -->
<mu1>50.0</mu1>
<mu2>50.0</mu2>
<kp>1000000.0</kp>
<kd>1.0</kd>
</gazebo>
<link name="bar_${note}">
<xacro:default_inertia_mass_inertial mass="0.03" inertial="0.01" />
<visual>
<origin xyz="0 0 ${-bar_height / 2}" rpy="0 0 0" />
<geometry>
<box size="${length} ${bar_width} ${bar_height}"/>
</geometry>
<!-- TODO material -->
<!-- <material name="oak_wood" /> -->
<material name="marimba_key" />
</visual>
<collision>
<origin xyz="0 0 ${-bar_height / 2}" rpy="0 0 0" />
<geometry>
<box size="${length} ${bar_width} ${bar_height}"/>
</geometry>
</collision>
</link>
<xacro:if value="$(arg bars_fixed_joint)">
<xacro:tams_fixedjoint name="bar_${note}/joint" parent="${parent}" child="bar_${note}" >
<origin xyz="${pos}" rpy="0 0 0" />
</xacro:tams_fixedjoint>
</xacro:if>
<xacro:unless value="$(arg bars_fixed_joint)">
<xacro:tams_z_joint name="bar_${note}/joint" parent="${parent}" child="bar_${note}" >
<origin xyz="${pos}" rpy="0 0 0" />
</xacro:tams_z_joint>
</xacro:unless>
<transmission name="bar_${note}/joint_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="bar_${note}/joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="bar_${note}/joint_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<!-- Optionally add a frame for lower part of the bar (closer to the player) -->
<xacro:if value="${add_low_frame}">
<link name="bar_${note}_low">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size=" 0 0 0"/>
</geometry>
</visual>
</link>
<xacro:tams_fixedjoint name="bar_${note}_low/joint" parent="bar_${note}" child="bar_${note}_low" >
<origin xyz="${length / 2 - 0.02} 0 0" rpy="0 0 0" />
</xacro:tams_fixedjoint>
</xacro:if>
</xacro:macro>
<!-- Wrapper for a row of bars, computes the position and length based on fixed measurements -->
<xacro:macro name="bar_in_row" params="note parent id left_x left_y left_z length_diff bar_length_left n_bars slope:=0 mirror:=1" >
<!-- mirror controls alignment of bars in row: -1 (right align) or 1 (left align) -->
<!-- mirror is set to -1 on the top row (sharp notes), and therefore is also used to control the low frame -->
<!-- if mirror is -1, add_low_frame becomes 1, if it's 1 then add_low_frame is 0 -->
<xacro:bar
note="${note}"
parent="${parent}"
id="${id}"
pos="${left_x + mirror * (id / n_bars) * (1 + slope) * length_diff/2} ${left_y + id * (bar_width + bar_gap)} ${left_z}"
length="${bar_length_left + (id / n_bars) * length_diff}"
add_low_frame="${(1 - mirror) / 2}"
/>
</xacro:macro>
<xacro:macro name="marimba" params="name">
<link name="${name}">
<default_inertial_with_mass mass="0.001" inertial="1" />
</link>
<gazebo reference="${name}" >
<turnGravityOff>false</turnGravityOff>
<selfCollide>true</selfCollide>
<!-- TODO material -->
<!--<material>Gazebo/Green</material>-->
<mu1>50.0</mu1>
<mu2>50.0</mu2>
<kp>1000000.0</kp>
<kd>1.0</kd>
</gazebo>
<!-- Bottom body -->
<gazebo reference="body_bottom">
<turnGravityOff>false</turnGravityOff>
<selfCollide>true</selfCollide>
<!-- TODO material -->
<!-- <material>chordophones/OakWood</material> -->
<mu1>50.0</mu1>
<mu2>50.0</mu2>
<kp>1000000.0</kp>
<kd>1.0</kd>
</gazebo>
<link name="body_bottom">
<inertial>
<mass value="7.5" />
<origin xyz="0 0 0" rpy="0 0 0" />
<inertia ixx="0.2" ixy="0" ixz="0" iyy="0.2" iyz="0" izz="0.05" />
</inertial>
<visual>
<origin xyz="${body_bottom_pos}" rpy="${body_bottom_rpy}" />
<geometry>
<!-- <mesh filename="package://chordophones/meshes/guzheng-body.stl" scale="0.001 0.001 0.001" /> -->
<box size="${body_bottom_width} ${body_bottom_length} ${body_bottom_height}"/>
</geometry>
<material name="gray" />
</visual>
<collision>
<origin xyz="${body_bottom_pos}" rpy="${body_bottom_rpy}" />
<geometry>
<box size="${body_bottom_width} ${body_bottom_length} ${body_bottom_height}"/>
</geometry>
</collision>
</link>
<xacro:tams_fixedjoint name="body_bottom/fixedjoint" parent="${name}" child="body_bottom" >
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:tams_fixedjoint>
<!-- Top body -->
<gazebo reference="body_top">
<turnGravityOff>false</turnGravityOff>
<selfCollide>true</selfCollide>
<!-- TODO material -->
<!-- <material>chordophones/OakWood</material> -->
<mu1>50.0</mu1>
<mu2>50.0</mu2>
<kp>1000000.0</kp>
<kd>1.0</kd>
</gazebo>
<link name="body_top">
<inertial>
<mass value="7.5" />
<origin xyz="0 0 0" rpy="0 0 0" />
<inertia ixx="0.2" ixy="0" ixz="0" iyy="0.2" iyz="0" izz="0.05" />
</inertial>
<visual>
<origin xyz="${body_top_pos}" rpy="${body_top_rpy}" />
<geometry>
<!-- <mesh filename="package://chordophones/meshes/guzheng-body.stl" scale="0.001 0.001 0.001" /> -->
<box size="${body_top_width} ${body_top_length} ${body_top_height}"/>
</geometry>
<material name="gray" />
</visual>
<collision>
<origin xyz="${body_top_pos}" rpy="${body_top_rpy}" />
<geometry>
<box size="${body_top_width} ${body_top_length} ${body_top_height}"/>
</geometry>
</collision>
</link>
<xacro:tams_fixedjoint name="body_top/fixedjoint" parent="${name}" child="body_top" >
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:tams_fixedjoint>
<!-- Left side box -->
<gazebo reference="body_left">
<turnGravityOff>false</turnGravityOff>
<selfCollide>true</selfCollide>
<!-- TODO material -->
<!-- <material>chordophones/OakWood</material> -->
<mu1>50.0</mu1>
<mu2>50.0</mu2>
<kp>1000000.0</kp>
<kd>1.0</kd>
</gazebo>
<link name="body_left">
<inertial>
<mass value="7.5" />
<origin xyz="0 0 0" rpy="0 0 0" />
<inertia ixx="0.2" ixy="0" ixz="0" iyy="0.2" iyz="0" izz="0.05" />
</inertial>
<visual>
<origin xyz="${side_left_pos}" rpy="0 0 1.57" />
<geometry>
<!-- <mesh filename="package://chordophones/meshes/guzheng-body.stl" scale="0.001 0.001 0.001" /> -->
<box size="${side_width} ${side_length_left} ${side_height}"/>
</geometry>
<material name="gray" />
</visual>
<collision>
<origin xyz="${side_left_pos}" rpy="0 0 1.57" />
<geometry>
<box size="${side_width} ${side_length_left} ${side_height}"/>
</geometry>
</collision>
</link>
<xacro:tams_fixedjoint name="body_left/fixedjoint" parent="${name}" child="body_left" >
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:tams_fixedjoint>
<!-- Right side box -->
<gazebo reference="body_right">
<turnGravityOff>false</turnGravityOff>
<selfCollide>true</selfCollide>
<!-- TODO material -->
<!-- <material>chordophones/OakWood</material> -->
<mu1>50.0</mu1>
<mu2>50.0</mu2>
<kp>1000000.0</kp>
<kd>1.0</kd>
</gazebo>
<link name="body_right">
<inertial>
<mass value="7.5" />
<origin xyz="0 0 0" rpy="0 0 0" />
<inertia ixx="0.2" ixy="0" ixz="0" iyy="0.2" iyz="0" izz="0.05" />
</inertial>
<visual>
<origin xyz="${side_right_pos}" rpy="0 0 1.57" />
<geometry>
<!-- <mesh filename="package://chordophones/meshes/guzheng-body.stl" scale="0.001 0.001 0.001" /> -->
<box size="${side_width} ${side_length_right} ${side_height}"/>
</geometry>
<material name="gray" />
</visual>
<collision>
<origin xyz="${side_right_pos}" rpy="0 0 1.57" />
<geometry>
<box size="${side_width} ${side_length_right} ${side_height}"/>
</geometry>
</collision>
</link>
<xacro:tams_fixedjoint name="body_right/fixedjoint" parent="${name}" child="body_right" >
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:tams_fixedjoint>
<!-- Bottom row of bars -->
<xacro:property name="body_bottom_length_diff" value="${bar_length_bottom_right - bar_length_bottom_left}" />
<xacro:bar_in_row note="c4" parent="body_bottom" id="0" left_x="${bottom_left_center_x}" left_y="${bottom_left_center_y}" left_z="${bottom_left_center_z}" length_diff="${body_bottom_length_diff}" bar_length_left="${bar_length_bottom_left}" n_bars="${n_bars_bottom}" slope="${body_bottom_slope}" />
<xacro:bar_in_row note="d4" parent="body_bottom" id="1" left_x="${bottom_left_center_x}" left_y="${bottom_left_center_y}" left_z="${bottom_left_center_z}" length_diff="${body_bottom_length_diff}" bar_length_left="${bar_length_bottom_left}" n_bars="${n_bars_bottom}" slope="${body_bottom_slope}" />
<xacro:bar_in_row note="e4" parent="body_bottom" id="2" left_x="${bottom_left_center_x}" left_y="${bottom_left_center_y}" left_z="${bottom_left_center_z}" length_diff="${body_bottom_length_diff}" bar_length_left="${bar_length_bottom_left}" n_bars="${n_bars_bottom}" slope="${body_bottom_slope}" />
<xacro:bar_in_row note="f4" parent="body_bottom" id="3" left_x="${bottom_left_center_x}" left_y="${bottom_left_center_y}" left_z="${bottom_left_center_z}" length_diff="${body_bottom_length_diff}" bar_length_left="${bar_length_bottom_left}" n_bars="${n_bars_bottom}" slope="${body_bottom_slope}" />
<xacro:bar_in_row note="g4" parent="body_bottom" id="4" left_x="${bottom_left_center_x}" left_y="${bottom_left_center_y}" left_z="${bottom_left_center_z}" length_diff="${body_bottom_length_diff}" bar_length_left="${bar_length_bottom_left}" n_bars="${n_bars_bottom}" slope="${body_bottom_slope}" />
<xacro:bar_in_row note="a4" parent="body_bottom" id="5" left_x="${bottom_left_center_x}" left_y="${bottom_left_center_y}" left_z="${bottom_left_center_z}" length_diff="${body_bottom_length_diff}" bar_length_left="${bar_length_bottom_left}" n_bars="${n_bars_bottom}" slope="${body_bottom_slope}" />
<xacro:bar_in_row note="b4" parent="body_bottom" id="6" left_x="${bottom_left_center_x}" left_y="${bottom_left_center_y}" left_z="${bottom_left_center_z}" length_diff="${body_bottom_length_diff}" bar_length_left="${bar_length_bottom_left}" n_bars="${n_bars_bottom}" slope="${body_bottom_slope}" />
<xacro:bar_in_row note="c5" parent="body_bottom" id="7" left_x="${bottom_left_center_x}" left_y="${bottom_left_center_y}" left_z="${bottom_left_center_z}" length_diff="${body_bottom_length_diff}" bar_length_left="${bar_length_bottom_left}" n_bars="${n_bars_bottom}" slope="${body_bottom_slope}" />
<xacro:bar_in_row note="d5" parent="body_bottom" id="8" left_x="${bottom_left_center_x}" left_y="${bottom_left_center_y}" left_z="${bottom_left_center_z}" length_diff="${body_bottom_length_diff}" bar_length_left="${bar_length_bottom_left}" n_bars="${n_bars_bottom}" slope="${body_bottom_slope}" />
<xacro:bar_in_row note="e5" parent="body_bottom" id="9" left_x="${bottom_left_center_x}" left_y="${bottom_left_center_y}" left_z="${bottom_left_center_z}" length_diff="${body_bottom_length_diff}" bar_length_left="${bar_length_bottom_left}" n_bars="${n_bars_bottom}" slope="${body_bottom_slope}" />
<xacro:bar_in_row note="f5" parent="body_bottom" id="10" left_x="${bottom_left_center_x}" left_y="${bottom_left_center_y}" left_z="${bottom_left_center_z}" length_diff="${body_bottom_length_diff}" bar_length_left="${bar_length_bottom_left}" n_bars="${n_bars_bottom}" slope="${body_bottom_slope}" />
<xacro:bar_in_row note="g5" parent="body_bottom" id="11" left_x="${bottom_left_center_x}" left_y="${bottom_left_center_y}" left_z="${bottom_left_center_z}" length_diff="${body_bottom_length_diff}" bar_length_left="${bar_length_bottom_left}" n_bars="${n_bars_bottom}" slope="${body_bottom_slope}" />
<xacro:bar_in_row note="a5" parent="body_bottom" id="12" left_x="${bottom_left_center_x}" left_y="${bottom_left_center_y}" left_z="${bottom_left_center_z}" length_diff="${body_bottom_length_diff}" bar_length_left="${bar_length_bottom_left}" n_bars="${n_bars_bottom}" slope="${body_bottom_slope}" />
<xacro:bar_in_row note="b5" parent="body_bottom" id="13" left_x="${bottom_left_center_x}" left_y="${bottom_left_center_y}" left_z="${bottom_left_center_z}" length_diff="${body_bottom_length_diff}" bar_length_left="${bar_length_bottom_left}" n_bars="${n_bars_bottom}" slope="${body_bottom_slope}" />
<xacro:bar_in_row note="c6" parent="body_bottom" id="14" left_x="${bottom_left_center_x}" left_y="${bottom_left_center_y}" left_z="${bottom_left_center_z}" length_diff="${body_bottom_length_diff}" bar_length_left="${bar_length_bottom_left}" n_bars="${n_bars_bottom}" slope="${body_bottom_slope}" />
<xacro:bar_in_row note="d6" parent="body_bottom" id="15" left_x="${bottom_left_center_x}" left_y="${bottom_left_center_y}" left_z="${bottom_left_center_z}" length_diff="${body_bottom_length_diff}" bar_length_left="${bar_length_bottom_left}" n_bars="${n_bars_bottom}" slope="${body_bottom_slope}" />
<xacro:bar_in_row note="e6" parent="body_bottom" id="16" left_x="${bottom_left_center_x}" left_y="${bottom_left_center_y}" left_z="${bottom_left_center_z}" length_diff="${body_bottom_length_diff}" bar_length_left="${bar_length_bottom_left}" n_bars="${n_bars_bottom}" slope="${body_bottom_slope}" />
<xacro:bar_in_row note="f6" parent="body_bottom" id="17" left_x="${bottom_left_center_x}" left_y="${bottom_left_center_y}" left_z="${bottom_left_center_z}" length_diff="${body_bottom_length_diff}" bar_length_left="${bar_length_bottom_left}" n_bars="${n_bars_bottom}" slope="${body_bottom_slope}" />
<xacro:bar_in_row note="g6" parent="body_bottom" id="18" left_x="${bottom_left_center_x}" left_y="${bottom_left_center_y}" left_z="${bottom_left_center_z}" length_diff="${body_bottom_length_diff}" bar_length_left="${bar_length_bottom_left}" n_bars="${n_bars_bottom}" slope="${body_bottom_slope}" />
<xacro:bar_in_row note="a6" parent="body_bottom" id="19" left_x="${bottom_left_center_x}" left_y="${bottom_left_center_y}" left_z="${bottom_left_center_z}" length_diff="${body_bottom_length_diff}" bar_length_left="${bar_length_bottom_left}" n_bars="${n_bars_bottom}" slope="${body_bottom_slope}" />
<xacro:bar_in_row note="b6" parent="body_bottom" id="20" left_x="${bottom_left_center_x}" left_y="${bottom_left_center_y}" left_z="${bottom_left_center_z}" length_diff="${body_bottom_length_diff}" bar_length_left="${bar_length_bottom_left}" n_bars="${n_bars_bottom}" slope="${body_bottom_slope}" />
<xacro:bar_in_row note="c7" parent="body_bottom" id="21" left_x="${bottom_left_center_x}" left_y="${bottom_left_center_y}" left_z="${bottom_left_center_z}" length_diff="${body_bottom_length_diff}" bar_length_left="${bar_length_bottom_left}" n_bars="${n_bars_bottom}" slope="${body_bottom_slope}" />
<!-- Top row of bars -->
<xacro:property name="body_top_length_diff" value="${bar_length_top_right - bar_length_top_left}" />
<xacro:bar_in_row note="cis4" parent="body_top" id="0" left_x="${top_left_center_x}" left_y="${top_left_center_y}" left_z="${top_left_center_z}" length_diff="${body_top_length_diff}" bar_length_left="${bar_length_top_left}" n_bars="${n_bars_top}" slope="${body_top_slope}" mirror="-1" />
<xacro:bar_in_row note="dis4" parent="body_top" id="1" left_x="${top_left_center_x}" left_y="${top_left_center_y}" left_z="${top_left_center_z}" length_diff="${body_top_length_diff}" bar_length_left="${bar_length_top_left}" n_bars="${n_bars_top}" slope="${body_top_slope}" mirror="-1" />
<xacro:bar_in_row note="fis4" parent="body_top" id="3" left_x="${top_left_center_x}" left_y="${top_left_center_y}" left_z="${top_left_center_z}" length_diff="${body_top_length_diff}" bar_length_left="${bar_length_top_left}" n_bars="${n_bars_top}" slope="${body_top_slope}" mirror="-1" />
<xacro:bar_in_row note="gis4" parent="body_top" id="4" left_x="${top_left_center_x}" left_y="${top_left_center_y}" left_z="${top_left_center_z}" length_diff="${body_top_length_diff}" bar_length_left="${bar_length_top_left}" n_bars="${n_bars_top}" slope="${body_top_slope}" mirror="-1" />
<xacro:bar_in_row note="ais4" parent="body_top" id="5" left_x="${top_left_center_x}" left_y="${top_left_center_y}" left_z="${top_left_center_z}" length_diff="${body_top_length_diff}" bar_length_left="${bar_length_top_left}" n_bars="${n_bars_top}" slope="${body_top_slope}" mirror="-1" />
<xacro:bar_in_row note="cis5" parent="body_top" id="7" left_x="${top_left_center_x}" left_y="${top_left_center_y}" left_z="${top_left_center_z}" length_diff="${body_top_length_diff}" bar_length_left="${bar_length_top_left}" n_bars="${n_bars_top}" slope="${body_top_slope}" mirror="-1" />
<xacro:bar_in_row note="dis5" parent="body_top" id="8" left_x="${top_left_center_x}" left_y="${top_left_center_y}" left_z="${top_left_center_z}" length_diff="${body_top_length_diff}" bar_length_left="${bar_length_top_left}" n_bars="${n_bars_top}" slope="${body_top_slope}" mirror="-1" />
<xacro:bar_in_row note="fis5" parent="body_top" id="10" left_x="${top_left_center_x}" left_y="${top_left_center_y}" left_z="${top_left_center_z}" length_diff="${body_top_length_diff}" bar_length_left="${bar_length_top_left}" n_bars="${n_bars_top}" slope="${body_top_slope}" mirror="-1" />
<xacro:bar_in_row note="gis5" parent="body_top" id="11" left_x="${top_left_center_x}" left_y="${top_left_center_y}" left_z="${top_left_center_z}" length_diff="${body_top_length_diff}" bar_length_left="${bar_length_top_left}" n_bars="${n_bars_top}" slope="${body_top_slope}" mirror="-1" />
<xacro:bar_in_row note="ais5" parent="body_top" id="12" left_x="${top_left_center_x}" left_y="${top_left_center_y}" left_z="${top_left_center_z}" length_diff="${body_top_length_diff}" bar_length_left="${bar_length_top_left}" n_bars="${n_bars_top}" slope="${body_top_slope}" mirror="-1" />
<xacro:bar_in_row note="cis6" parent="body_top" id="14" left_x="${top_left_center_x}" left_y="${top_left_center_y}" left_z="${top_left_center_z}" length_diff="${body_top_length_diff}" bar_length_left="${bar_length_top_left}" n_bars="${n_bars_top}" slope="${body_top_slope}" mirror="-1" />
<xacro:bar_in_row note="dis6" parent="body_top" id="15" left_x="${top_left_center_x}" left_y="${top_left_center_y}" left_z="${top_left_center_z}" length_diff="${body_top_length_diff}" bar_length_left="${bar_length_top_left}" n_bars="${n_bars_top}" slope="${body_top_slope}" mirror="-1" />
<xacro:bar_in_row note="fis6" parent="body_top" id="17" left_x="${top_left_center_x}" left_y="${top_left_center_y}" left_z="${top_left_center_z}" length_diff="${body_top_length_diff}" bar_length_left="${bar_length_top_left}" n_bars="${n_bars_top}" slope="${body_top_slope}" mirror="-1" />
<xacro:bar_in_row note="gis6" parent="body_top" id="18" left_x="${top_left_center_x}" left_y="${top_left_center_y}" left_z="${top_left_center_z}" length_diff="${body_top_length_diff}" bar_length_left="${bar_length_top_left}" n_bars="${n_bars_top}" slope="${body_top_slope}" mirror="-1" />
<xacro:bar_in_row note="ais6" parent="body_top" id="19" left_x="${top_left_center_x}" left_y="${top_left_center_y}" left_z="${top_left_center_z}" length_diff="${body_top_length_diff}" bar_length_left="${bar_length_top_left}" n_bars="${n_bars_top}" slope="${body_top_slope}" mirror="-1" />
</xacro:macro>
<xacro:marimba name="marimba" />
</robot>