init
This commit is contained in:
BIN
cordless_drill/materials/textures/cordless_drill.png
Normal file
BIN
cordless_drill/materials/textures/cordless_drill.png
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 1.3 MiB |
138
cordless_drill/meshes/cordless_drill.dae
Normal file
138
cordless_drill/meshes/cordless_drill.dae
Normal file
File diff suppressed because one or more lines are too long
BIN
cordless_drill/meshes/cordless_drill.stl
Normal file
BIN
cordless_drill/meshes/cordless_drill.stl
Normal file
Binary file not shown.
35
cordless_drill/model-1_2.sdf
Normal file
35
cordless_drill/model-1_2.sdf
Normal file
@@ -0,0 +1,35 @@
|
||||
<?xml version="1.0" ?>
|
||||
<gazebo version="1.2">
|
||||
<model name="drill">
|
||||
<link name="link">
|
||||
<inertial>
|
||||
<pose>-0.00637 -0.008 0.13254 0 0 0</pose>
|
||||
<inertia>
|
||||
<ixx>0.01331127</ixx>
|
||||
<ixy>-0.00030365</ixy>
|
||||
<ixz>-0.00034148</ixz>
|
||||
<iyy>0.01157659</iyy>
|
||||
<iyz>0.00088073</iyz>
|
||||
<izz>0.00378028</izz>
|
||||
</inertia>
|
||||
<mass>1.50251902</mass>
|
||||
</inertial>
|
||||
<collision name="collision">
|
||||
<pose>0 0 -0.09 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://cordless_drill/meshes/cordless_drill.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<pose>0 0 -0.09 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://cordless_drill/meshes/cordless_drill.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
</gazebo>
|
||||
43
cordless_drill/model-1_3.sdf
Normal file
43
cordless_drill/model-1_3.sdf
Normal file
@@ -0,0 +1,43 @@
|
||||
<?xml version="1.0" ?>
|
||||
<sdf version="1.3">
|
||||
<model name="drill">
|
||||
<link name="link">
|
||||
<inertial>
|
||||
<pose>-0.00637 -0.008 0.13254 0 0 0</pose>
|
||||
<inertia>
|
||||
<ixx>0.01331127</ixx>
|
||||
<ixy>-0.00030365</ixy>
|
||||
<ixz>-0.00034148</ixz>
|
||||
<iyy>0.01157659</iyy>
|
||||
<iyz>0.00088073</iyz>
|
||||
<izz>0.00378028</izz>
|
||||
</inertia>
|
||||
<mass>1.50251902</mass>
|
||||
</inertial>
|
||||
<collision name="collision">
|
||||
<pose>0 0 -0.09 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://cordless_drill/meshes/cordless_drill.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode>
|
||||
<max_vel>0.1</max_vel>
|
||||
<min_depth>0.001</min_depth>
|
||||
</ode>
|
||||
</contact>
|
||||
</surface>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<pose>0 0 -0.09 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://cordless_drill/meshes/cordless_drill.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
</sdf>
|
||||
43
cordless_drill/model-1_4.sdf
Normal file
43
cordless_drill/model-1_4.sdf
Normal file
@@ -0,0 +1,43 @@
|
||||
<?xml version="1.0" ?>
|
||||
<sdf version="1.4">
|
||||
<model name="drill">
|
||||
<link name="link">
|
||||
<inertial>
|
||||
<pose>-0.00637 -0.008 0.13254 0 0 0</pose>
|
||||
<inertia>
|
||||
<ixx>0.01331127</ixx>
|
||||
<ixy>-0.00030365</ixy>
|
||||
<ixz>-0.00034148</ixz>
|
||||
<iyy>0.01157659</iyy>
|
||||
<iyz>0.00088073</iyz>
|
||||
<izz>0.00378028</izz>
|
||||
</inertia>
|
||||
<mass>1.50251902</mass>
|
||||
</inertial>
|
||||
<collision name="collision">
|
||||
<pose>0 0 -0.09 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://cordless_drill/meshes/cordless_drill.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode>
|
||||
<max_vel>0.1</max_vel>
|
||||
<min_depth>0.001</min_depth>
|
||||
</ode>
|
||||
</contact>
|
||||
</surface>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<pose>0 0 -0.09 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://cordless_drill/meshes/cordless_drill.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
</sdf>
|
||||
19
cordless_drill/model.config
Normal file
19
cordless_drill/model.config
Normal file
@@ -0,0 +1,19 @@
|
||||
<?xml version="1.0"?>
|
||||
|
||||
<model>
|
||||
<name>Cordless Drill</name>
|
||||
<version>1.0</version>
|
||||
<sdf version="1.2">model-1_2.sdf</sdf>
|
||||
<sdf version="1.3">model-1_3.sdf</sdf>
|
||||
<sdf version="1.4">model-1_4.sdf</sdf>
|
||||
<sdf version="1.5">model.sdf</sdf>
|
||||
|
||||
<author>
|
||||
<name>John Hsu</name>
|
||||
<email>hsu@osrfoundation.org</email>
|
||||
</author>
|
||||
|
||||
<description>
|
||||
A cordless drill..
|
||||
</description>
|
||||
</model>
|
||||
43
cordless_drill/model.sdf
Normal file
43
cordless_drill/model.sdf
Normal file
@@ -0,0 +1,43 @@
|
||||
<?xml version="1.0" ?>
|
||||
<sdf version="1.5">
|
||||
<model name="drill">
|
||||
<link name="link">
|
||||
<inertial>
|
||||
<pose>-0.00637 -0.008 0.13254 0 0 0</pose>
|
||||
<inertia>
|
||||
<ixx>0.01331127</ixx>
|
||||
<ixy>-0.00030365</ixy>
|
||||
<ixz>-0.00034148</ixz>
|
||||
<iyy>0.01157659</iyy>
|
||||
<iyz>0.00088073</iyz>
|
||||
<izz>0.00378028</izz>
|
||||
</inertia>
|
||||
<mass>1.50251902</mass>
|
||||
</inertial>
|
||||
<collision name="collision">
|
||||
<pose>0 0 -0.09 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://cordless_drill/meshes/cordless_drill.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
<surface>
|
||||
<contact>
|
||||
<ode>
|
||||
<max_vel>0.1</max_vel>
|
||||
<min_depth>0.001</min_depth>
|
||||
</ode>
|
||||
</contact>
|
||||
</surface>
|
||||
</collision>
|
||||
<visual name="visual">
|
||||
<pose>0 0 -0.09 0 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
<uri>model://cordless_drill/meshes/cordless_drill.dae</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</visual>
|
||||
</link>
|
||||
</model>
|
||||
</sdf>
|
||||
Reference in New Issue
Block a user