mirror of
https://github.com/osrf/gazebo_models.git
synced 2025-09-15 12:58:56 +08:00
Fix round_tin meshes, add contact properties to ball_bearing
This commit is contained in:
parent
ea2b7cc852
commit
c28d18d80a
@ -36,6 +36,14 @@
|
||||
<radius><%= r %></radius>
|
||||
</sphere>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode>
|
||||
<max_vel>0.1</max_vel>
|
||||
<min_depth>0.0001</min_depth>
|
||||
</ode>
|
||||
</contact>
|
||||
</surface>
|
||||
</collision>
|
||||
|
||||
<visual name="visual">
|
||||
|
||||
@ -1,4 +1,5 @@
|
||||
<?xml version="1.0" ?>
|
||||
|
||||
<sdf version="1.5">
|
||||
<model name="ball_bearing">
|
||||
<link name="link">
|
||||
@ -21,6 +22,14 @@
|
||||
<radius>0.003</radius>
|
||||
</sphere>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode>
|
||||
<max_vel>0.1</max_vel>
|
||||
<min_depth>0.0001</min_depth>
|
||||
</ode>
|
||||
</contact>
|
||||
</surface>
|
||||
</collision>
|
||||
|
||||
<visual name="visual">
|
||||
|
||||
File diff suppressed because one or more lines are too long
@ -9,11 +9,11 @@
|
||||
height = 0.02817
|
||||
|
||||
# mesh height offset
|
||||
mesh_dz = 0.00017
|
||||
mesh_dz = 0.001
|
||||
mesh_pose = "<pose>0 0 #{mesh_dz} 0 0 0</pose>"
|
||||
|
||||
# base cylinder height
|
||||
cylinder_height = 0.001
|
||||
cylinder_height = 0.002
|
||||
cylinder_pose = "<pose>0 0 #{cylinder_height/2} 0 0 0</pose>"
|
||||
|
||||
# Inertia: approximate as a thin-walled cylindrical tube (not accurate)
|
||||
@ -56,7 +56,7 @@
|
||||
</surface>
|
||||
</collision>
|
||||
|
||||
<visual name="visual_mesh">
|
||||
<visual name="visual_cylinder">
|
||||
<%= cylinder_pose %>
|
||||
<geometry>
|
||||
<cylinder>
|
||||
|
||||
@ -12,16 +12,16 @@
|
||||
<ixz>0</ixz>
|
||||
<iyy>1.93146783725e-05</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>3.5680000000000004e-05</izz>
|
||||
<izz>3.568e-05</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
|
||||
<collision name="collision_cylinder">
|
||||
<pose>0 0 0.0005 0 0 0</pose>
|
||||
<pose>0 0 0.001 0 0 0</pose>
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.04</radius>
|
||||
<length>0.001</length>
|
||||
<length>0.002</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<surface>
|
||||
@ -34,12 +34,12 @@
|
||||
</surface>
|
||||
</collision>
|
||||
|
||||
<visual name="visual_mesh">
|
||||
<pose>0 0 0.0005 0 0 0</pose>
|
||||
<visual name="visual_cylinder">
|
||||
<pose>0 0 0.001 0 0 0</pose>
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.04</radius>
|
||||
<length>0.001</length>
|
||||
<length>0.002</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<material>
|
||||
@ -51,7 +51,7 @@
|
||||
</visual>
|
||||
|
||||
<collision name="collision_mesh">
|
||||
<pose>0 0 0.00017 0 0 0</pose>
|
||||
<pose>0 0 0.001 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://round_tin_base/meshes/round_tin_base.dae</uri>
|
||||
@ -68,7 +68,7 @@
|
||||
</collision>
|
||||
|
||||
<visual name="visual_mesh">
|
||||
<pose>0 0 0.00017 0 0 0</pose>
|
||||
<pose>0 0 0.001 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://round_tin_base/meshes/round_tin_base.dae</uri>
|
||||
|
||||
File diff suppressed because one or more lines are too long
@ -4,21 +4,29 @@
|
||||
|
||||
# Geometry
|
||||
|
||||
d = 0.084
|
||||
r = d/2.0
|
||||
diameter = 0.084
|
||||
radius = diameter/2.0
|
||||
height = 0.0115
|
||||
|
||||
# mesh height offset
|
||||
mesh_dz = 0.0010
|
||||
mesh_pose = "<pose>0 0 #{mesh_dz} 0 0 0</pose>"
|
||||
|
||||
# base cylinder height
|
||||
cylinder_height = 0.002
|
||||
cylinder_pose = "<pose>0 0 #{cylinder_height/2} 0 0 0</pose>"
|
||||
|
||||
# Inertia: approximate as a thin-walled cylindrical tube (not accurate)
|
||||
mass = 0.0142
|
||||
ixx = mass*(r**2/2 + height**2/12)
|
||||
iyy = mass*(r**2/2 + height**2/12)
|
||||
izz = mass*r**2
|
||||
ixx = mass*(radius**2/2 + height**2/12)
|
||||
iyy = ixx
|
||||
izz = mass*radius**2
|
||||
%>
|
||||
<sdf version="1.5">
|
||||
<model name="round_tin_top">
|
||||
<link name="link">
|
||||
<pose>0 0 <%= height/2 %> 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose>0 0 <%= height/2 %> 0 0 0</pose>
|
||||
<mass><%= mass %></mass>
|
||||
<inertia>
|
||||
<ixx><%= ixx %></ixx>
|
||||
@ -30,7 +38,42 @@
|
||||
</inertia>
|
||||
</inertial>
|
||||
|
||||
<collision name="collision_cylinder">
|
||||
<%= cylinder_pose %>
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius><%= radius %></radius>
|
||||
<length><%= cylinder_height %></length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode>
|
||||
<max_vel>0.1</max_vel>
|
||||
<min_depth>0.0001</min_depth>
|
||||
</ode>
|
||||
</contact>
|
||||
</surface>
|
||||
</collision>
|
||||
|
||||
<visual name="visual_cylinder">
|
||||
<%= cylinder_pose %>
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius><%= radius %></radius>
|
||||
<length><%= cylinder_height %></length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||||
<name>Gazebo/Gray</name>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<collision name="collision">
|
||||
<%= mesh_pose %>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://round_tin_top/meshes/round_tin_top.dae</uri>
|
||||
@ -47,6 +90,7 @@
|
||||
</collision>
|
||||
|
||||
<visual name="visual">
|
||||
<%= mesh_pose %>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://round_tin_top/meshes/round_tin_top.dae</uri>
|
||||
|
||||
@ -1,21 +1,57 @@
|
||||
<?xml version="1.0" ?>
|
||||
|
||||
<sdf version="1.5">
|
||||
<model name="round_tin_top">
|
||||
<link name="link">
|
||||
<pose>0 0 0.00575 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose>0 0 0.00575 0 0 0</pose>
|
||||
<mass>0.0142</mass>
|
||||
<inertia>
|
||||
<ixx>1.2680895833333335e-05</ixx>
|
||||
<ixx>1.26808958333333e-05</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>1.2680895833333335e-05</iyy>
|
||||
<iyy>1.26808958333333e-05</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>2.5048800000000003e-05</izz>
|
||||
<izz>2.50488e-05</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
|
||||
<collision name="collision_cylinder">
|
||||
<pose>0 0 0.001 0 0 0</pose>
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.042</radius>
|
||||
<length>0.002</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode>
|
||||
<max_vel>0.1</max_vel>
|
||||
<min_depth>0.0001</min_depth>
|
||||
</ode>
|
||||
</contact>
|
||||
</surface>
|
||||
</collision>
|
||||
|
||||
<visual name="visual_cylinder">
|
||||
<pose>0 0 0.001 0 0 0</pose>
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.042</radius>
|
||||
<length>0.002</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||||
<name>Gazebo/Gray</name>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<collision name="collision">
|
||||
<pose>0 0 0.001 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://round_tin_top/meshes/round_tin_top.dae</uri>
|
||||
@ -32,6 +68,7 @@
|
||||
</collision>
|
||||
|
||||
<visual name="visual">
|
||||
<pose>0 0 0.001 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://round_tin_top/meshes/round_tin_top.dae</uri>
|
||||
|
||||
Loading…
Reference in New Issue
Block a user