mirror of
https://github.com/osrf/gazebo_models.git
synced 2025-09-15 12:58:56 +08:00
add contact parameters
This commit is contained in:
parent
efd8aae953
commit
8741ef5df4
@ -23,6 +23,14 @@
|
|||||||
<radius>0.0392125</radius>
|
<radius>0.0392125</radius>
|
||||||
</cylinder>
|
</cylinder>
|
||||||
</geometry>
|
</geometry>
|
||||||
|
<surface>
|
||||||
|
<contact>
|
||||||
|
<ode>
|
||||||
|
<max_vel>0.1</max_vel>
|
||||||
|
<min_depth>0.001</min_depth>
|
||||||
|
</ode>
|
||||||
|
</contact>
|
||||||
|
</surface>
|
||||||
</collision>
|
</collision>
|
||||||
|
|
||||||
<visual name="visual">
|
<visual name="visual">
|
||||||
|
|||||||
@ -22,6 +22,14 @@
|
|||||||
<size>0.059 0.052 0.0075</size>
|
<size>0.059 0.052 0.0075</size>
|
||||||
</box>
|
</box>
|
||||||
</geometry>
|
</geometry>
|
||||||
|
<surface>
|
||||||
|
<contact>
|
||||||
|
<ode>
|
||||||
|
<max_vel>0.1</max_vel>
|
||||||
|
<min_depth>0.001</min_depth>
|
||||||
|
</ode>
|
||||||
|
</contact>
|
||||||
|
</surface>
|
||||||
</collision>
|
</collision>
|
||||||
<collision name='collision_2'>
|
<collision name='collision_2'>
|
||||||
<pose frame=''>0 0.08 0.00375 0 0 0</pose>
|
<pose frame=''>0 0.08 0.00375 0 0 0</pose>
|
||||||
@ -30,6 +38,14 @@
|
|||||||
<size>0.031 0.11 0.0075</size>
|
<size>0.031 0.11 0.0075</size>
|
||||||
</box>
|
</box>
|
||||||
</geometry>
|
</geometry>
|
||||||
|
<surface>
|
||||||
|
<contact>
|
||||||
|
<ode>
|
||||||
|
<max_vel>0.1</max_vel>
|
||||||
|
<min_depth>0.001</min_depth>
|
||||||
|
</ode>
|
||||||
|
</contact>
|
||||||
|
</surface>
|
||||||
</collision>
|
</collision>
|
||||||
|
|
||||||
<visual name="visual">
|
<visual name="visual">
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user