-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathwheel.xacro
372 lines (343 loc) · 12.2 KB
/
wheel.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
<?xml version="1.0"?>
<!--
Robot model adapted from https://github.com/CIR-KIT/steer_drive_ros/blob/kinetic-devel/steer_drive_controller/test/common/urdf/wheel.xacro
Modifications:
<transmissions> elements have been updated and added to 'front_steer'.
Update inertials.
Remove dependency on externally defined parameters.
-->
<robot name="wheel" xmlns:xacro="http://wiki.ros.org/xacro">
<!-- Include xacro for materials and inertials -->
<xacro:include filename="$(find steer_bot_description)/urdf/materials.xacro"/>
<xacro:include filename="$(find steer_bot_description)/urdf/inertials.xacro"/>
<!-- Properties -->
<xacro:property name="steer_effort" value="10.0"/>
<xacro:property name="steer_velocity" value="5.0"/>
<xacro:property name="steer_limit_deg" value="45.0"/>
<!-- Bicycle model front steering link (required for steer_drive_controller) -->
<xacro:macro name="front_steer"
params="
name
parent
steer_radius
steer_thickness
steer_mass
base_length
base_width
axle_offset
steer_height">
<link name="${name}_steer_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="${steer_radius}" length="${steer_thickness}"/>
</geometry>
<material name="yellow" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="${steer_radius}" length="${steer_thickness}"/>
</geometry>
</collision>
<xacro:solid_cylinder_inertial
rpy="0 0 0" xyz="0 0 0"
mass="${steer_mass}"
radius="${steer_radius}" length="${steer_thickness}" />
</link>
<joint name="${name}_steer_joint" type="revolute">
<parent link="${parent}_link"/>
<child link="${name}_steer_link"/>
<origin xyz="${base_length/2-axle_offset} 0 ${steer_height}" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit effort="${steer_effort}"
lower="${-180.0 * deg_to_rad}" upper="${180.0 * deg_to_rad}"
velocity="${steer_velocity}"/>
</joint>
<transmission name="${name}_steer_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="${name}_steer_joint_motor">
<mechanicalReduction>1</mechanicalReduction>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</actuator>
<joint name="${name}_steer_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
</transmission>
<gazebo reference="${name}_steer_link">
<material>Gazebo/Yellow</material>
</gazebo>
</xacro:macro>
<!-- Car steering model front (steerable) wheel links (left/right) -->
<xacro:macro name="front_wheel_lr"
params="
name
parent
reflect
wheel_radius
wheel_thickness
wheel_mass
steer_radius
steer_thickness
steer_mass
base_length
base_width
axle_offset
steer_height">
<link name="${name}_steer_link2">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="${steer_radius}" length="${steer_thickness}"/>
</geometry>
<material name="blue" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="${steer_radius}" length="${steer_thickness}"/>
</geometry>
</collision>
<xacro:solid_cylinder_inertial
rpy="0 0 0" xyz="0 0 0"
mass="${steer_mass}"
radius="${steer_radius}" length="${steer_thickness}" />
</link>
<joint name="${name}_steer_joint2" type="revolute">
<parent link="${parent}_link"/>
<child link="${name}_steer_link2"/>
<origin xyz="${base_length/2-axle_offset} ${reflect*(base_width/2+axle_offset)} ${steer_height*2}" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit effort="${steer_effort}"
lower="${steer_limit_deg * deg_to_rad * -1.0}" upper="${steer_limit_deg * deg_to_rad}"
velocity="${steer_velocity}"/>
</joint>
<link name="${name}_steer_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="${steer_radius}" length="${steer_thickness}"/>
</geometry>
<material name="blue" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="${steer_radius}" length="${steer_thickness}"/>
</geometry>
</collision>
<xacro:solid_cylinder_inertial
rpy="0 0 0" xyz="0 0 0"
mass="${steer_mass}"
radius="${steer_radius}" length="${steer_thickness}" />
</link>
<joint name="${name}_shock_absorber" type="prismatic">
<parent link="${name}_steer_link2"/>
<child link="${name}_steer_link"/>
<origin xyz="0 0 ${-steer_height}" rpy="0 0 0"/>
<axis xyz="0 0 -1"/>
<limit effort="1000"
lower="-0.03" upper="0.03"
velocity="1000"/>
<dynamics damping="500" spring_stiffness="10000" spring_reference="0.08" friction="0.001"/>
</joint>
<transmission name="${name}_shock_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${name}_shock_absorber">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="${name}_shock_act">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<link name="${name}_wheel_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_thickness}"/>
</geometry>
<material name="red" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_thickness}"/>
</geometry>
</collision>
<xacro:solid_cylinder_inertial
rpy="0 0 0" xyz="0 0 0"
mass="${wheel_mass}"
radius="${wheel_radius}" length="${wheel_thickness}" />
</link>
<joint name="${name}_wheel_joint" type="continuous">
<parent link="${name}_steer_link"/>
<child link="${name}_wheel_link"/>
<origin xyz="0 0 ${-steer_height}" rpy="${-90 * deg_to_rad} 0 0"/>
<axis xyz="0 0 1"/>
</joint>
<transmission name="${name}_steer_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="${name}_steer_joint_motor">
<mechanicalReduction>1</mechanicalReduction>
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</actuator>
<joint name="${name}_steer_joint">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
</transmission>
<transmission name="${name}_wheel_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="${name}_wheel_joint_motor">
<mechanicalReduction>1</mechanicalReduction>
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</actuator>
<joint name="${name}_wheel_joint">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
</transmission>
<gazebo reference="${name}_steer_link">
<material>Gazebo/Blue</material>
</gazebo>
<gazebo reference="${name}_wheel_link">
<material>Gazebo/Red</material>
</gazebo>
</xacro:macro>
<!-- Bicycle model rear wheel link (required for steer_drive_controller) -->
<xacro:macro name="rear_wheel"
params="
name
parent
wheel_radius
wheel_thickness
wheel_mass
*origin">
<link name="${name}_wheel_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_thickness}"/>
</geometry>
<material name="yellow" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_thickness}"/>
</geometry>
</collision>
<xacro:solid_cylinder_inertial
rpy="0 0 0" xyz="0 0 0"
mass="${wheel_mass}"
radius="${wheel_radius}" length="${wheel_thickness}" />
</link>
<joint name="${name}_wheel_joint" type="continuous">
<parent link="${parent}_link"/>
<child link="${name}_wheel_link"/>
<xacro:insert_block name="origin"/>
<axis xyz="0 0 1"/>
</joint>
<transmission name="${name}_wheel_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="${name}_wheel_joint_motor">
<mechanicalReduction>1</mechanicalReduction>
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</actuator>
<joint name="${name}_wheel_joint">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
</transmission>
<gazebo reference="${name}_wheel_link">
<material>Gazebo/Yellow</material>
</gazebo>
</xacro:macro>
<!-- Bicycle model front wheel link (passive - no transmission) -->
<xacro:macro name="front_wheel"
params="
name
parent
wheel_radius
wheel_thickness
wheel_mass
*origin">
<link name="${name}_wheel_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_thickness}"/>
</geometry>
<material name="yellow" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_thickness}"/>
</geometry>
</collision>
<xacro:solid_cylinder_inertial
rpy="0 0 0" xyz="0 0 0"
mass="${wheel_mass}"
radius="${wheel_radius}" length="${wheel_thickness}" />
</link>
<joint name="${name}_wheel_joint" type="continuous">
<parent link="${parent}_link"/>
<child link="${name}_wheel_link"/>
<xacro:insert_block name="origin"/>
<axis xyz="0 0 1"/>
</joint>
<gazebo reference="${name}_wheel_link">
<material>Gazebo/Yellow</material>
</gazebo>
<gazebo reference="${name}_wheel_joint">
<provideFeedback>true</provideFeedback>
</gazebo>
</xacro:macro>
<!-- Car steering model rear wheel links (left/right) -->
<xacro:macro name="rear_wheel_lr"
params="
name
parent
wheel_radius
wheel_thickness
wheel_mass
*origin">
<link name="${name}_wheel_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_thickness}"/>
</geometry>
<material name="red" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_thickness}"/>
</geometry>
</collision>
<xacro:solid_cylinder_inertial
rpy="0 0 0" xyz="0 0 0"
mass="${wheel_mass}"
radius="${wheel_radius}" length="${wheel_thickness}" />
</link>
<joint name="${name}_wheel_joint" type="continuous">
<parent link="${parent}_link"/>
<child link="${name}_wheel_link"/>
<xacro:insert_block name="origin"/>
<axis xyz="0 0 1"/>
</joint>
<transmission name="${name}_wheel_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="${name}_wheel_joint_motor">
<mechanicalReduction>1</mechanicalReduction>
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</actuator>
<joint name="${name}_wheel_joint">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
</transmission>
<gazebo reference="${name}_wheel_link">
<material>Gazebo/Red</material>
</gazebo>
</xacro:macro>
</robot>