Skip to content

Commit 8782197

Browse files
use bullet
1 parent b8cf6c9 commit 8782197

File tree

1 file changed

+63
-18
lines changed

1 file changed

+63
-18
lines changed

nav2_minimal_tb3_sim/urdf/gz_waffle_gps.sdf.xacro

Lines changed: 63 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -215,23 +215,23 @@
215215
</geometry>
216216
<surface>
217217
<friction>
218-
<ode>
218+
<bullet>
219219
<mu>1</mu>
220220
<mu2>1</mu2>
221221
<slip1>0.035</slip1>
222222
<slip2>0</slip2>
223223
<fdir1>0 0 1</fdir1>
224-
</ode>
224+
</bullet>
225225
</friction>
226226
<contact>
227-
<ode>
227+
<bullet>
228228
<soft_cfm>0</soft_cfm>
229229
<soft_erp>0.2</soft_erp>
230230
<kp>1e+5</kp>
231231
<kd>1</kd>
232232
<max_vel>0.01</max_vel>
233233
<min_depth>0.001</min_depth>
234-
</ode>
234+
</bullet>
235235
</contact>
236236
</surface>
237237
</collision>
@@ -275,23 +275,23 @@
275275
</geometry>
276276
<surface>
277277
<friction>
278-
<ode>
278+
<bullet>
279279
<mu>1</mu>
280280
<mu2>1</mu2>
281281
<slip1>0.035</slip1>
282282
<slip2>0</slip2>
283283
<fdir1>0 0 1</fdir1>
284-
</ode>
284+
</bullet>
285285
</friction>
286286
<contact>
287-
<ode>
287+
<bullet>
288288
<soft_cfm>0</soft_cfm>
289289
<soft_erp>0.2</soft_erp>
290290
<kp>1e+5</kp>
291291
<kd>1</kd>
292292
<max_vel>0.01</max_vel>
293293
<min_depth>0.001</min_depth>
294-
</ode>
294+
</bullet>
295295
</contact>
296296
</surface>
297297
</collision>
@@ -311,7 +311,7 @@
311311
</link>
312312

313313
<link name='caster_back_right_link'>
314-
<pose>-0.177 -0.064 -0.004 0 0 0</pose>
314+
<pose>-0.177 -0.064 -0.004 -1.57 0 0</pose>
315315
<inertial>
316316
<mass>0.001</mass>
317317
<inertia>
@@ -323,29 +323,52 @@
323323
<izz>0.00001</izz>
324324
</inertia>
325325
</inertial>
326-
<collision name='collision'>
326+
<collision name='caster_back_right_collision'>
327327
<geometry>
328328
<sphere>
329-
<radius>0.005000</radius>
329+
<radius>0.0060000</radius>
330330
</sphere>
331331
</geometry>
332332
<surface>
333+
<friction>
334+
<bullet>
335+
<mu>1</mu>
336+
<mu2>1</mu2>
337+
<slip1>0.035</slip1>
338+
<slip2>0</slip2>
339+
<fdir1>0 0 1</fdir1>
340+
</bullet>
341+
</friction>
333342
<contact>
334-
<ode>
343+
<bullet>
335344
<soft_cfm>0</soft_cfm>
336345
<soft_erp>0.2</soft_erp>
337346
<kp>1e+5</kp>
338347
<kd>1</kd>
339348
<max_vel>0.01</max_vel>
340349
<min_depth>0.001</min_depth>
341-
</ode>
350+
</bullet>
342351
</contact>
343352
</surface>
344353
</collision>
354+
355+
<visual name="sphere_visual">
356+
<geometry>
357+
<sphere>
358+
<radius>0.0060000</radius>
359+
</sphere>
360+
</geometry>
361+
<material>
362+
<ambient>0 0 1 1</ambient>
363+
<diffuse>0 0 1 1</diffuse>
364+
<specular>0 0 1 1</specular>
365+
</material>
366+
</visual>
345367
</link>
346368

347369
<link name='caster_back_left_link'>
348-
<pose>-0.177 0.064 -0.004 0 0 0</pose>
370+
<pose>-0.177 0.064 -0.004 -1.57 0 0</pose>
371+
349372
<inertial>
350373
<mass>0.001</mass>
351374
<inertia>
@@ -357,28 +380,50 @@
357380
<izz>0.00001</izz>
358381
</inertia>
359382
</inertial>
360-
<collision name='collision'>
383+
<collision name='caster_back_left_collision'>
361384
<geometry>
362385
<sphere>
363-
<radius>0.005000</radius>
386+
<radius>0.0060000</radius>
364387
</sphere>
365388
</geometry>
366389
<surface>
390+
<friction>
391+
<bullet>
392+
<mu>1</mu>
393+
<mu2>1</mu2>
394+
<slip1>0.035</slip1>
395+
<slip2>0</slip2>
396+
<fdir1>0 0 1</fdir1>
397+
</bullet>
398+
</friction>
367399
<contact>
368-
<ode>
400+
<bullet>
369401
<soft_cfm>0</soft_cfm>
370402
<soft_erp>0.2</soft_erp>
371403
<kp>1e+5</kp>
372404
<kd>1</kd>
373405
<max_vel>0.01</max_vel>
374406
<min_depth>0.001</min_depth>
375-
</ode>
407+
</bullet>
376408
</contact>
377409
</surface>
378410
</collision>
411+
<visual name="sphere_visual">
412+
<geometry>
413+
<sphere>
414+
<radius>0.0060000</radius>
415+
</sphere>
416+
</geometry>
417+
<material>
418+
<ambient>0 0 1 1</ambient>
419+
<diffuse>0 0 1 1</diffuse>
420+
<specular>0 0 1 1</specular>
421+
</material>
422+
</visual>
379423
</link>
380424

381425
<link name="camera_link">
426+
<pose>0.069 -0.047 0.107 0 0 0</pose>
382427
<inertial>
383428
<pose>0.069 -0.047 0.107 0 0 0</pose>
384429
<inertia>

0 commit comments

Comments
 (0)