This commit is contained in:
Quella777
2025-08-25 16:30:02 +08:00
commit 32cc2a8e96
1633 changed files with 289456 additions and 0 deletions

16
wooden_board/model.config Normal file
View File

@@ -0,0 +1,16 @@
<?xml version="1.0"?>
<model>
<name>Wooden board</name>
<version>1.0</version>
<sdf version='1.5'>model.sdf</sdf>
<author>
<name>Jackie Kay</name>
<email>jackie@osrfoundation.org</email>
</author>
<description>
A wooden board with no pegs. Part of the ARAT set.
</description>
</model>

98
wooden_board/model.rsdf Normal file
View File

@@ -0,0 +1,98 @@
<?xml version="1.0" ?>
<sdf version="1.5">
<model name="wooden_board">
<link name="base">
<%
# Wood block with dimensions 33 x 10 x 1 cm
# SI units (length in meters)
# Geometry
dx = 0.1016
dy = 0.3302
dz = 0.01046
# Inertia
mass = 0.2765
ixx = mass/12.0 * (dy**2 + dz**2)
iyy = mass/12.0 * (dz**2 + dx**2)
izz = mass/12.0 * (dx**2 + dy**2)
inchToMeter = 0.0254
tee_nut_diameter = 0.5 * inchToMeter
tee_nut_radius = tee_nut_diameter / 2
tee_nut_length = dz*1.01
tee_nut_pos = {
"tee_nut_1" => [0.0, -0.116, 0.0],
"tee_nut_2" => [0.0, -0.038, 0.0],
"tee_nut_3" => [0.0, 0.038, 0.0],
"tee_nut_4" => [0.0, 0.116, 0.0],
}
%>
<pose>0 0 <%= dz/2 %> 0 0 0</pose>
<inertial>
<mass><%= mass %></mass>
<inertia>
<ixx><%= ixx %></ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy><%= iyy %></iyy>
<iyz>0</iyz>
<izz><%= izz %></izz>
</inertia>
</inertial>
<collision name="collision">
<geometry>
<box>
<size><%= dx %> <%= dy %> <%= dz %></size>
</box>
</geometry>
<surface>
<contact>
<ode>
<max_vel>0.1</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
</surface>
</collision>
<visual name="visual">
<geometry>
<box>
<size><%= dx %> <%= dy %> <%= dz %></size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Wood</name>
</script>
</material>
</visual>
<% tee_nut_pos.keys.each do |k|
name = k
pos = tee_nut_pos[k]
%>
<%= "<visual name='#{name}'>" %>
<pose><%= pos.join(' ') %> 0 0 0</pose>
<geometry>
<cylinder>
<radius><%= tee_nut_radius %></radius>
<length><%= tee_nut_length %></length>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<% end %>
</link>
</model>
</sdf>

132
wooden_board/model.sdf Normal file
View File

@@ -0,0 +1,132 @@
<?xml version="1.0" ?>
<sdf version="1.5">
<model name="wooden_board">
<link name="base">
<pose>0 0 0.00523 0 0 0</pose>
<inertial>
<mass>0.2765</mass>
<inertia>
<ixx>0.0025148009472833336</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.00024037001228333334</iyy>
<iyz>0</iyz>
<izz>0.002750128908333333</izz>
</inertia>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.1016 0.3302 0.01046</size>
</box>
</geometry>
<surface>
<contact>
<!-- Red Pine coefficients for longitudinal axis of the wood
according to:
http://www.fpl.fs.fed.us/documnts/fplgtr/fplgtr113/ch04.pdf -->
<poissons_ratio>0.347</poissons_ratio>
<elastic_modulus>8.8e+09</elastic_modulus>
<ode>
<kp>100000</kp>
<kd>100</kd>
<max_vel>100.0</max_vel>
<min_depth>0.001</min_depth>
</ode>
</contact>
<friction>
<torsional>
<coefficient>1.0</coefficient>
<use_patch_radius>0</use_patch_radius>
<surface_radius>0.01</surface_radius>
</torsional>
</friction>
</surface>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.1016 0.3302 0.01046</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Wood</name>
</script>
</material>
</visual>
<visual name='tee_nut_1'>
<pose>0.0 -0.116 0.0 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.00635</radius>
<length>0.0105646</length>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<visual name='tee_nut_2'>
<pose>0.0 -0.038 0.0 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.00635</radius>
<length>0.0105646</length>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<visual name='tee_nut_3'>
<pose>0.0 0.038 0.0 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.00635</radius>
<length>0.0105646</length>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<visual name='tee_nut_4'>
<pose>0.0 0.116 0.0 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.00635</radius>
<length>0.0105646</length>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
</model>
</sdf>