init
This commit is contained in:
16
wooden_case/model.config
Normal file
16
wooden_case/model.config
Normal file
@@ -0,0 +1,16 @@
|
||||
<?xml version="1.0"?>
|
||||
|
||||
<model>
|
||||
<name>Wooden case</name>
|
||||
<version>1.0</version>
|
||||
<sdf version='1.5'>model.sdf</sdf>
|
||||
|
||||
<author>
|
||||
<name>Jackie Kay</name>
|
||||
<email>jackie@osrfoundation.org</email>
|
||||
</author>
|
||||
|
||||
<description>
|
||||
An open wooden box. Part of the ARAT set.
|
||||
</description>
|
||||
</model>
|
254
wooden_case/model.rsdf
Normal file
254
wooden_case/model.rsdf
Normal file
@@ -0,0 +1,254 @@
|
||||
<?xml version="1.0" ?>
|
||||
<%
|
||||
# Wooden case for ARAT models
|
||||
# SI units (length in meters)
|
||||
|
||||
# Geometry
|
||||
inchToMeter = 0.0254
|
||||
width = 23 * inchToMeter
|
||||
height = 14 * inchToMeter
|
||||
depth = 5 * inchToMeter
|
||||
thickness = 0.75 * inchToMeter
|
||||
|
||||
d = depth
|
||||
h = height
|
||||
t = thickness
|
||||
w = width
|
||||
|
||||
# blocks on bottom of case
|
||||
block_size = [0.108, 0.050, 0.024]
|
||||
block_dx = 0.5*(depth - block_size[0])
|
||||
block_dy = 0.5*(w - block_size[1]) - 0.052
|
||||
block_dz = -0.5 * block_size[2]
|
||||
base_pieces = {
|
||||
"back" => {:size => [t, w-2*t, h-2*t], :pos => [-0.5*(d-t), 0, h/2]},
|
||||
"bottom" => {:size => [d, w, t], :pos => [0, 0, t / 2.0]},
|
||||
"top" => {:size => [d, w, t], :pos => [0, 0, h - t / 2.0]},
|
||||
"left" => {:size => [d, t, h - 2*t], :pos => [0, -0.5*(w-t), 0.5*h]},
|
||||
"right" => {:size => [d, t, h - 2*t], :pos => [0, 0.5*(w-t), 0.5*h]},
|
||||
"block_left" => {:size => block_size, :pos => [block_dx, -block_dy, block_dz]},
|
||||
"block_right" => {:size => block_size, :pos => [block_dx, block_dy, block_dz]},
|
||||
}
|
||||
# Material
|
||||
# Assume soft wood with density of 500 kg / m^3
|
||||
density = 500
|
||||
|
||||
# Surface parameters
|
||||
surface = "
|
||||
<contact>
|
||||
<ode>
|
||||
<max_vel>0.1</max_vel>
|
||||
<min_depth>0.001</min_depth>
|
||||
</ode>
|
||||
</contact>"
|
||||
%>
|
||||
<sdf version="1.5">
|
||||
<model name="wooden_case">
|
||||
<link name="base">
|
||||
<%
|
||||
# Compute inertia
|
||||
|
||||
# Compute mass of each component
|
||||
# mass: total mass
|
||||
mass = 0
|
||||
base_pieces.keys.each do |k|
|
||||
dx = base_pieces[k][:size][0]
|
||||
dy = base_pieces[k][:size][1]
|
||||
dz = base_pieces[k][:size][2]
|
||||
m = density * dx * dy * dz
|
||||
mass += m
|
||||
base_pieces[k][:mass] = m
|
||||
|
||||
ixx = m/12.0 * (dy**2 + dz**2)
|
||||
iyy = m/12.0 * (dz**2 + dx**2)
|
||||
izz = m/12.0 * (dx**2 + dy**2)
|
||||
base_pieces[k][:ixx] = ixx
|
||||
base_pieces[k][:iyy] = iyy
|
||||
base_pieces[k][:izz] = izz
|
||||
end
|
||||
|
||||
# Compute lumped center of mass
|
||||
cx_sum = 0.0
|
||||
cy_sum = 0.0
|
||||
cz_sum = 0.0
|
||||
base_pieces.keys.each do |k|
|
||||
m = base_pieces[k][:mass]
|
||||
pos = base_pieces[k][:pos]
|
||||
cx_sum += m * pos[0]
|
||||
cy_sum += m * pos[1]
|
||||
cz_sum += m * pos[2]
|
||||
end
|
||||
c = [cx_sum / mass, cy_sum / mass, cz_sum / mass]
|
||||
|
||||
# Compute lumped moments of inertia with respect to center of mass
|
||||
lumped_ixx = 0.0
|
||||
lumped_iyy = 0.0
|
||||
lumped_izz = 0.0
|
||||
lumped_ixy = 0.0
|
||||
lumped_ixz = 0.0
|
||||
lumped_iyz = 0.0
|
||||
base_pieces.keys.each do |k|
|
||||
m = base_pieces[k][:mass]
|
||||
pos = base_pieces[k][:pos]
|
||||
ixx = base_pieces[k][:ixx]
|
||||
iyy = base_pieces[k][:iyy]
|
||||
izz = base_pieces[k][:izz]
|
||||
cx = pos[0] - c[0]
|
||||
cy = pos[1] - c[1]
|
||||
cz = pos[2] - c[2]
|
||||
|
||||
lumped_ixx += ixx + m*(cy*cy + cz*cz)
|
||||
lumped_iyy += iyy + m*(cz*cz + cx*cx)
|
||||
lumped_izz += izz + m*(cx*cx + cy*cy)
|
||||
lumped_ixy -= m*cx*cy
|
||||
lumped_ixz -= m*cx*cz
|
||||
lumped_iyz -= m*cy*cz
|
||||
end
|
||||
ixx = lumped_ixx
|
||||
iyy = lumped_iyy
|
||||
izz = lumped_izz
|
||||
ixy = lumped_ixy
|
||||
ixz = lumped_ixz
|
||||
iyz = lumped_iyz
|
||||
%>
|
||||
<pose>0 0 <%= block_size[2] %> 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose><%= c.join(' ') %> 0 0 0</pose>
|
||||
<mass><%= mass %></mass>
|
||||
<inertia>
|
||||
<ixx><%= ixx %></ixx>
|
||||
<ixy><%= ixy %></ixy>
|
||||
<ixz><%= ixz %></ixz>
|
||||
<iyy><%= iyy %></iyy>
|
||||
<iyz><%= iyz %></iyz>
|
||||
<izz><%= izz %></izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<% base_pieces.keys.each do |k|
|
||||
name = k
|
||||
dx = base_pieces[k][:size][0]
|
||||
dy = base_pieces[k][:size][1]
|
||||
dz = base_pieces[k][:size][2]
|
||||
pose = base_pieces[k][:pos].join(' ') + " 0 0 0"
|
||||
%>
|
||||
<%= "<collision name='collision_#{name}'>" %>
|
||||
<pose><%= pose %></pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size><%= dx %> <%= dy %> <%= dz %></size>
|
||||
</box>
|
||||
</geometry>
|
||||
<surface>
|
||||
<%= surface %>
|
||||
</surface>
|
||||
</collision>
|
||||
<%= "<visual name='visual_#{name}'>" %>
|
||||
<pose><%= pose %></pose>
|
||||
<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>
|
||||
<% end %>
|
||||
</link>
|
||||
|
||||
<link name="lid">
|
||||
<% # Size and inertia of box lid
|
||||
dx = height
|
||||
dy = width
|
||||
dz = t
|
||||
pos = [(dx+depth + block_size[2]-t)/2, 0, t/2]
|
||||
mass = density * dx * dy * dz
|
||||
ixx = mass/12.0 * (dy**2 + dz**2)
|
||||
iyy = mass/12.0 * (dz**2 + dx**2)
|
||||
izz = mass/12.0 * (dx**2 + dy**2)
|
||||
|
||||
tee_nut_diameter = 0.5 * inchToMeter
|
||||
tee_nut_radius = tee_nut_diameter / 2
|
||||
tee_nut_length = t*1.01
|
||||
tee_nut_pos = {
|
||||
"tee_nut_1" => [0.122, -0.216, 0.0],
|
||||
"tee_nut_2" => [0.122, -0.088, 0.0],
|
||||
"tee_nut_3" => [0.122, 0.088, 0.0],
|
||||
"tee_nut_4" => [0.122, 0.216, 0.0],
|
||||
}
|
||||
%>
|
||||
<pose><%= pos.join(' ') %> 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>
|
||||
<%= surface %>
|
||||
</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>
|
||||
|
||||
<joint name="lid_hinge" type="revolute">
|
||||
<pose><%= -h/2 %> 0 <%= t %> 0 0 0</pose>
|
||||
<parent>base</parent>
|
||||
<child>lid</child>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<upper><%= Math::PI/6 %></upper>
|
||||
<lower><%= -Math::PI/2 %></lower>
|
||||
</limit>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
</model>
|
||||
</sdf>
|
475
wooden_case/model.sdf
Normal file
475
wooden_case/model.sdf
Normal file
@@ -0,0 +1,475 @@
|
||||
<?xml version="1.0" ?>
|
||||
|
||||
<sdf version="1.5">
|
||||
<model name="wooden_case">
|
||||
<link name="base">
|
||||
|
||||
<pose>0 0 0.024 0 0 0</pose>
|
||||
<inertial>
|
||||
<pose>-0.02218446808213116 0.0 0.17159249678128843 0 0 0</pose>
|
||||
<mass>3.9626366887499986</mass>
|
||||
<inertia>
|
||||
<ixx>0.2135364168029657</ixx>
|
||||
<ixy>0.0</ixy>
|
||||
<ixz>0.0007793770806417083</ixz>
|
||||
<iyy>0.07089428398599372</iyy>
|
||||
<iyz>0.0</iyz>
|
||||
<izz>0.15460392299497075</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
|
||||
<collision name='collision_back'>
|
||||
<pose>-0.053975 0 0.17779999999999999 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.019049999999999997 0.5460999999999999 0.3175</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_back'>
|
||||
<pose>-0.053975 0 0.17779999999999999 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.019049999999999997 0.5460999999999999 0.3175</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||||
<name>Gazebo/Wood</name>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<collision name='collision_bottom'>
|
||||
<pose>0 0 0.009524999999999999 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.127 0.5841999999999999 0.019049999999999997</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_bottom'>
|
||||
<pose>0 0 0.009524999999999999 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.127 0.5841999999999999 0.019049999999999997</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||||
<name>Gazebo/Wood</name>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<collision name='collision_top'>
|
||||
<pose>0 0 0.34607499999999997 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.127 0.5841999999999999 0.019049999999999997</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_top'>
|
||||
<pose>0 0 0.34607499999999997 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.127 0.5841999999999999 0.019049999999999997</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||||
<name>Gazebo/Wood</name>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<collision name='collision_left'>
|
||||
<pose>0 -0.28257499999999997 0.17779999999999999 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.127 0.019049999999999997 0.3175</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_left'>
|
||||
<pose>0 -0.28257499999999997 0.17779999999999999 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.127 0.019049999999999997 0.3175</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||||
<name>Gazebo/Wood</name>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<collision name='collision_right'>
|
||||
<pose>0 0.28257499999999997 0.17779999999999999 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.127 0.019049999999999997 0.3175</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_right'>
|
||||
<pose>0 0.28257499999999997 0.17779999999999999 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.127 0.019049999999999997 0.3175</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||||
<name>Gazebo/Wood</name>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<collision name='collision_block_left'>
|
||||
<pose>0.009500000000000001 -0.21509999999999996 -0.012 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.108 0.05 0.024</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_block_left'>
|
||||
<pose>0.009500000000000001 -0.21509999999999996 -0.012 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.108 0.05 0.024</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||||
<name>Gazebo/Wood</name>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
<collision name='collision_block_right'>
|
||||
<pose>0.009500000000000001 0.21509999999999996 -0.012 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.108 0.05 0.024</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_block_right'>
|
||||
<pose>0.009500000000000001 0.21509999999999996 -0.012 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.108 0.05 0.024</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||||
<name>Gazebo/Wood</name>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
</link>
|
||||
|
||||
<link name="lid">
|
||||
|
||||
<pose>0.24377499999999996 0 0.009524999999999999 0 0 0</pose>
|
||||
<inertial>
|
||||
<mass>1.9787379779999992</mass>
|
||||
<inertia>
|
||||
<ixx>0.05633673842708405</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>0.020911016446734258</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>0.07712807338064145</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<collision name='collision'>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.35559999999999997 0.5841999999999999 0.019049999999999997</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.35559999999999997 0.5841999999999999 0.019049999999999997</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.122 -0.216 0.0 0 0 0</pose>
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.00635</radius>
|
||||
<length>0.019240499999999997</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.122 -0.088 0.0 0 0 0</pose>
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.00635</radius>
|
||||
<length>0.019240499999999997</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.122 0.088 0.0 0 0 0</pose>
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.00635</radius>
|
||||
<length>0.019240499999999997</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.122 0.216 0.0 0 0 0</pose>
|
||||
<geometry>
|
||||
<cylinder>
|
||||
<radius>0.00635</radius>
|
||||
<length>0.019240499999999997</length>
|
||||
</cylinder>
|
||||
</geometry>
|
||||
<material>
|
||||
<script>
|
||||
<uri>file://media/materials/scripts/gazebo.material</uri>
|
||||
<name>Gazebo/Grey</name>
|
||||
</script>
|
||||
</material>
|
||||
</visual>
|
||||
|
||||
</link>
|
||||
|
||||
<joint name="lid_hinge" type="revolute">
|
||||
<pose>-0.17779999999999999 0 0.019049999999999997 0 0 0</pose>
|
||||
<parent>base</parent>
|
||||
<child>lid</child>
|
||||
<axis>
|
||||
<xyz>0 1 0</xyz>
|
||||
<limit>
|
||||
<upper>0.5235987755982988</upper>
|
||||
<lower>-1.5707963267948966</lower>
|
||||
</limit>
|
||||
</axis>
|
||||
</joint>
|
||||
|
||||
</model>
|
||||
</sdf>
|
Reference in New Issue
Block a user