merge with default

This commit is contained in:
Steve Peters 2013-04-19 11:23:24 -07:00
commit 988cad4400
210 changed files with 17990 additions and 3267 deletions

View File

@ -12,29 +12,10 @@ string (TOLOWER ${PROJECT_NAME} PROJECT_NAME_LOWER)
exec_program(date ARGS -u +%Y-%m-%-dT%H:%M:%S OUTPUT_VARIABLE CURRENT_DATE)
#include (FindPkgConfig)
#if (PKG_CONFIG_FOUND)
# pkg_check_modules(GAZEBO gazebo)
# pkg_check_modules(OGRE OGRE)
# pkg_check_modules(CEGUI CEGUI)
#endif()
#
#include_directories(
# ${GAZEBO_INCLUDE_DIRS}
# ${OGRE_INCLUDE_DIRS}
# ${CEGUI_INCLUDE_DIRS}
#)
#
#link_directories(
# ${GAZEBO_LIBRARY_DIRS}
# ${OGRE_LIBRARY_DIRS}
# ${CEGUI_LIBRARY_DIRS}
#)
set (dirs
bookshelf
bowl
brick_box_3x1x3
cabinet
camera
coke_can
@ -46,6 +27,7 @@ cube_20k
double_pendulum_with_base
dumpster
fast_food
fire_hose_long
gas_station
ground_plane
hammer
@ -68,6 +50,7 @@ nist_simple_ramp_120
nist_stairs_120
office_building
pioneer2dx
pioneer3at
polaris_ranger_ev
powerplant
pr2
@ -77,8 +60,8 @@ simple_arm
simple_arm_gripper
simple_gripper
speed_limit_sign
stereo_camera
starting_pen
stereo_camera
stop_sign
sun
table
@ -116,4 +99,3 @@ message (STATUS "Install path: ${CMAKE_INSTALL_PREFIX}/models")
# This must always be last!
include(CPack)

View File

@ -1,17 +0,0 @@
<?xml version="1.0"?>
<model>
<name>Bookshelf</name>
<version>1.0</version>
<sdf version='1.2'>model.sdf</sdf>
<sdf version='1.3'>model-1_3.sdf</sdf>
<author>
<name>Nate Koenig</name>
<email>nate@osrfoundation.org</email>
</author>
<description>
A wooden bookshelf.
</description>
</model>

165
bookshelf/model-1_2.sdf Normal file
View File

@ -0,0 +1,165 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<model name="bookshelf">
<static>true</static>
<link name="link">
<inertial>
<mass>1.0</mass>
</inertial>
<collision name="back">
<pose>0 0.005 0.6 0 0 0</pose>
<geometry>
<box>
<size>0.9 0.01 1.2</size>
</box>
</geometry>
</collision>
<visual name="visual1">
<pose>0 0.005 0.6 0 0 0</pose>
<geometry>
<box>
<size>0.9 0.01 1.2</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Wood</name>
</script>
</material>
</visual>
<collision name="left_side">
<pose>0.45 -0.195 0.6 0 0 0</pose>
<geometry>
<box>
<size>0.02 0.4 1.2</size>
</box>
</geometry>
</collision>
<visual name="visual2">
<pose>0.45 -0.195 0.6 0 0 0</pose>
<geometry>
<box>
<size>0.02 0.4 1.2</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Wood</name>
</script>
</material>
</visual>
<collision name="right_side">
<pose>-0.45 -0.195 0.6 0 0 0</pose>
<geometry>
<box>
<size>0.02 0.4 1.2</size>
</box>
</geometry>
</collision>
<visual name="visual3">
<pose>-0.45 -0.195 0.6 0 0 0</pose>
<geometry>
<box>
<size>0.02 0.4 1.2</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Wood</name>
</script>
</material>
</visual>
<collision name="bottom">
<pose>0 -0.195 0.03 0 0 0</pose>
<geometry>
<box>
<size>0.88 0.4 0.06</size>
</box>
</geometry>
</collision>
<visual name="visual4">
<pose>0 -0.195 0.03 0 0 0</pose>
<geometry>
<box>
<size>0.88 0.4 0.06</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Wood</name>
</script>
</material>
</visual>
<collision name="top">
<pose>0 -0.195 1.19 0 0 0</pose>
<geometry>
<box>
<size>0.88 0.4 0.02</size>
</box>
</geometry>
</collision>
<visual name="visual5">
<pose>0 -0.195 1.19 0 0 0</pose>
<geometry>
<box>
<size>0.88 0.4 0.02</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Wood</name>
</script>
</material>
</visual>
<collision name="low_shelf">
<pose>0 -0.195 0.43 0 0 0</pose>
<geometry>
<box>
<size>0.88 0.4 0.02</size>
</box>
</geometry>
</collision>
<visual name="visual6">
<pose>0 -0.195 0.43 0 0 0</pose>
<geometry>
<box>
<size>0.88 0.4 0.02</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Wood</name>
</script>
</material>
</visual>
<collision name="high_shelf">
<pose>0 -0.195 0.8 0 0 0</pose>
<geometry>
<box>
<size>0.88 0.4 0.02</size>
</box>
</geometry>
</collision>
<visual name="visual7">
<pose>0 -0.195 0.8 0 0 0</pose>
<geometry>
<box>
<size>0.88 0.4 0.02</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Wood</name>
</script>
</material>
</visual>
</link>
</model>
</gazebo>

View File

@ -3,8 +3,9 @@
<model>
<name>Bookshelf</name>
<version>1.0</version>
<sdf version='1.2'>model.sdf</sdf>
<sdf version='1.2'>model-1_2.sdf</sdf>
<sdf version='1.3'>model-1_3.sdf</sdf>
<sdf version='1.4'>model.sdf</sdf>
<author>
<name>Nate Koenig</name>

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.4">
<model name="bookshelf">
<static>true</static>
<link name="link">
@ -162,4 +162,4 @@
</visual>
</link>
</model>
</gazebo>
</sdf>

View File

@ -1,17 +0,0 @@
<?xml version="1.0"?>
<model>
<name>Bowl</name>
<version>1.0</version>
<sdf version="1.2">model.sdf</sdf>
<sdf version="1.3">model-1_3.sdf</sdf>
<author>
<name>Nate Koenig</name>
<email>nate@osrfoundation.org</email>
</author>
<description>
A simple bowl.
</description>
</model>

25
bowl/model-1_2.sdf Normal file
View File

@ -0,0 +1,25 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<model name="bowl">
<link name="link">
<inertial>
<mass>0.1</mass>
</inertial>
<collision name="collision">
<geometry>
<cylinder>
<radius>0.098</radius>
<length>0.035</length>
</cylinder>
</geometry>
</collision>
<visual name="visual">
<geometry>
<mesh>
<uri>model://bowl/meshes/bowl.dae</uri>
</mesh>
</geometry>
</visual>
</link>
</model>
</gazebo>

View File

@ -3,8 +3,9 @@
<model>
<name>Bowl</name>
<version>1.0</version>
<sdf version="1.2">model.sdf</sdf>
<sdf version="1.2">model-1_2.sdf</sdf>
<sdf version="1.3">model-1_3.sdf</sdf>
<sdf version="1.4">model.sdf</sdf>
<author>
<name>Nate Koenig</name>

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.4">
<model name="bowl">
<link name="link">
<inertial>
@ -22,4 +22,4 @@
</visual>
</link>
</model>
</gazebo>
</sdf>

View File

@ -0,0 +1,31 @@
<?xml version="1.0" ?>
<sdf version="1.3">
<model name="brick_box_3x1x3">
<static>true</static>
<link name="chassis">
<pose>0 0 1.5 0 0 0</pose>
<collision name="collision">
<geometry>
<box>
<size>3.0 1.0 3.0</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<mesh>
<uri>model://brick_box_3x1x3/meshes/simple_box.dae</uri>
<scale>3.0 1.0 3.0</scale>
</mesh>
</geometry>
<material>
<script>
<uri>model://brick_box_3x1x3/materials/scripts</uri>
<uri>model://brick_box_3x1x3/materials/textures</uri>
<name>BrickBox/Diffuse</name>
</script>
</material>
</visual>
</link>
</model>
</sdf>

View File

@ -3,7 +3,8 @@
<model>
<name>Brick Box 3x1x3</name>
<version>1.0</version>
<sdf version="1.3">model.sdf</sdf>
<sdf version="1.3">model-1_4.sdf</sdf>
<sdf version="1.4">model.sdf</sdf>
<description>
Brick Box 3x1x3

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<sdf version="1.3">
<sdf version="1.4">
<model name="brick_box_3x1x3">
<static>true</static>
<link name="chassis">

View File

@ -1,17 +0,0 @@
<?xml version="1.0"?>
<model>
<name>Cabinet</name>
<version>1.0</version>
<sdf version='1.2'>model.sdf</sdf>
<sdf version='1.3'>model-1_3.sdf</sdf>
<author>
<name>Nate Koenig</name>
<email>nate@osrfoundation.org</email>
</author>
<description>
A wooden cabinet.
</description>
</model>

152
cabinet/model-1_2.sdf Normal file
View File

@ -0,0 +1,152 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<model name="cabinet">
<static>true</static>
<link name="cabinet_bottom_plate">
<inertial>
<pose>0 0 -1 0 0 0</pose>
<inertia>
<ixx>2.050000</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>2.050000</iyy>
<iyz>0</iyz>
<izz>2.050000</izz>
</inertia>
<mass>25.000000</mass>
</inertial>
<collision name="cabinet_bottom_plate_geom">
<pose>0 0 0.010000 0 0 0</pose>
<geometry>
<box>
<size>0.450000 0.450000 0.020000</size>
</box>
</geometry>
</collision>
<visual name="cabinet_bottom_plate_geom_visual">
<pose>0 0 0.010000 0 0 0</pose>
<geometry>
<box>
<size>0.450000 0.450000 0.020000</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Wood</name>
</script>
</material>
</visual>
<collision name="cabinet_bottom_plate_geom_cabinet_back_plate">
<pose>0.235000 0 0.510000 0 0 0</pose>
<geometry>
<box>
<size>0.020000 0.450000 1.020000</size>
</box>
</geometry>
</collision>
<visual name="cabinet_bottom_plate_geom_cabinet_back_plate_visual">
<pose>0.235000 0 0.510000 0 0 0</pose>
<geometry>
<box>
<size>0.020000 0.450000 1.020000</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Wood</name>
</script>
</material>
</visual>
<collision name="cabinet_bottom_plate_geom_cabinet_left_plate">
<pose>0 0.235000 0.510000 0 0 0</pose>
<geometry>
<box>
<size>0.450000 0.020000 1.020000</size>
</box>
</geometry>
</collision>
<visual name="cabinet_bottom_plate_geom_cabinet_left_plate_visual">
<pose>0 0.235000 0.510000 0 0 0</pose>
<geometry>
<box>
<size>0.450000 0.020000 1.020000</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Wood</name>
</script>
</material>
</visual>
<collision name="cabinet_bottom_plate_geom_cabinet_middle_plate">
<pose>0 0 0.510000 0 0 0</pose>
<geometry>
<box>
<size>0.450000 0.450000 0.020000</size>
</box>
</geometry>
</collision>
<visual name="cabinet_bottom_plate_geom_cabinet_middle_plate_visual">
<pose>0 0 0.510000 0 0 0</pose>
<geometry>
<box>
<size>0.450000 0.450000 0.020000</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Wood</name>
</script>
</material>
</visual>
<collision name="cabinet_bottom_plate_geom_cabinet_right_plate">
<pose>0 -0.235000 0.510000 0 0 0</pose>
<geometry>
<box>
<size>0.450000 0.020000 1.020000</size>
</box>
</geometry>
</collision>
<visual name="cabinet_bottom_plate_geom_cabinet_right_plate_visual">
<pose>0 -0.235000 0.510000 0 0 0</pose>
<geometry>
<box>
<size>0.450000 0.020000 1.020000</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Wood</name>
</script>
</material>
</visual>
<collision name="cabinet_bottom_plate_geom_cabinet_top_plate">
<pose>0 0 1.010000 0 0 0</pose>
<geometry>
<box>
<size>0.450000 0.450000 0.020000</size>
</box>
</geometry>
</collision>
<visual name="cabinet_bottom_plate_geom_cabinet_top_plate_visual">
<pose>0 0 1.010000 0 0 0</pose>
<geometry>
<box>
<size>0.450000 0.450000 0.020000</size>
</box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Wood</name>
</script>
</material>
</visual>
</link>
</model>
</gazebo>

View File

@ -3,8 +3,9 @@
<model>
<name>Cabinet</name>
<version>1.0</version>
<sdf version='1.2'>model.sdf</sdf>
<sdf version='1.2'>model-1_2.sdf</sdf>
<sdf version='1.3'>model-1_3.sdf</sdf>
<sdf version='1.4'>model.sdf</sdf>
<author>
<name>Nate Koenig</name>

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.4">
<model name="cabinet">
<static>true</static>
<link name="cabinet_bottom_plate">
@ -149,4 +149,4 @@
</visual>
</link>
</model>
</gazebo>
</sdf>

View File

@ -1,17 +0,0 @@
<?xml version="1.0"?>
<model>
<name>Camera</name>
<version>1.0</version>
<sdf version="1.2">model.sdf</sdf>
<sdf version="1.3">model-1_3.sdf</sdf>
<author>
<name>Nate Koenig</name>
<email>nate@osrfoundation.org</email>
</author>
<description>
A simple camera with a box for visualization.
</description>
</model>

35
camera/model-1_2.sdf Normal file
View File

@ -0,0 +1,35 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<model name="camera">
<link name="link">
<gravity>false</gravity>
<pose>0.05 0.05 0.05 0 0 0</pose>
<inertial>
<mass>0.1</mass>
</inertial>
<visual name="visual">
<geometry>
<box>
<size>0.1 0.1 0.1</size>
</box>
</geometry>
</visual>
<sensor name="camera" type="camera">
<camera>
<horizontal_fov>1.047</horizontal_fov>
<image>
<width>320</width>
<height>240</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>true</visualize>
</sensor>
</link>
</model>
</gazebo>

View File

@ -3,8 +3,9 @@
<model>
<name>Camera</name>
<version>1.0</version>
<sdf version="1.2">model.sdf</sdf>
<sdf version="1.2">model-1_2.sdf</sdf>
<sdf version="1.3">model-1_3.sdf</sdf>
<sdf version="1.4">model.sdf</sdf>
<author>
<name>Nate Koenig</name>

View File

@ -1,12 +1,18 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.4">
<model name="camera">
<link name="link">
<gravity>false</gravity>
<pose>0.05 0.05 0.05 0 0 0</pose>
<inertial>
<mass>0.1</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.1 0.1 0.1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
@ -32,4 +38,4 @@
</sensor>
</link>
</model>
</gazebo>
</sdf>

View File

@ -1,17 +0,0 @@
<?xml version="1.0"?>
<model>
<name>Coke Can</name>
<version>1.0</version>
<sdf version="1.2">model.sdf</sdf>
<sdf version="1.3">model-1_3.sdf</sdf>
<author>
<name>John Hsu</name>
<email>hsu@osrfoundation.org</email>
</author>
<description>
A can of Coke.
</description>
</model>

34
coke_can/model-1_2.sdf Normal file
View File

@ -0,0 +1,34 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<model name="coke_can">
<link name="link">
<inertial>
<mass>0.390</mass>
<inertia>
<ixx>0.00058</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.00058</iyy>
<iyz>0</iyz>
<izz>0.00019</izz>
</inertia>
</inertial>
<collision name="collision">
<pose>0 0 -0.46 0 0 0</pose>
<geometry>
<mesh>
<uri>model://coke_can/meshes/coke_can.dae</uri>
</mesh>
</geometry>
</collision>
<visual name="visual">
<pose>0 0 -0.46 0 0 0</pose>
<geometry>
<mesh>
<uri>model://coke_can/meshes/coke_can.dae</uri>
</mesh>
</geometry>
</visual>
</link>
</model>
</gazebo>

View File

@ -3,8 +3,9 @@
<model>
<name>Coke Can</name>
<version>1.0</version>
<sdf version="1.2">model.sdf</sdf>
<sdf version="1.2">model-1_2.sdf</sdf>
<sdf version="1.3">model-1_3.sdf</sdf>
<sdf version="1.4">model.sdf</sdf>
<author>
<name>John Hsu</name>

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.4">
<model name="coke_can">
<link name="link">
<inertial>
@ -31,4 +31,4 @@
</visual>
</link>
</model>
</gazebo>
</sdf>

View File

@ -0,0 +1,21 @@
<?xml version="1.0"?>
<sdf version="1.3">
<model name="Construction Barrel">
<link name="link">
<collision name="collision">
<geometry>
<mesh>
<uri>model://construction_barrel/meshes/construction_barrel.dae</uri>
</mesh>
</geometry>
</collision>
<visual name="visual">
<geometry>
<mesh>
<uri>model://construction_barrel/meshes/construction_barrel.dae</uri>
</mesh>
</geometry>
</visual>
</link>
</model>
</sdf>

View File

@ -3,7 +3,8 @@
<model>
<name>Construction Barrel</name>
<version>1.0</version>
<sdf version="1.3">model.sdf</sdf>
<sdf version="1.3">model-1_3.sdf</sdf>
<sdf version="1.4">model.sdf</sdf>
<author>
<name>Cole Biesemeyer</name>

View File

@ -1,5 +1,5 @@
<?xml version="1.0"?>
<sdf version="1.3">
<sdf version="1.4">
<model name="Construction Barrel">
<link name="link">
<collision name="collision">

View File

@ -1,17 +0,0 @@
<?xml version="1.0"?>
<model>
<name>Cordless Drill</name>
<version>1.0</version>
<sdf version="1.2">model.sdf</sdf>
<sdf version="1.3">model-1_3.sdf</sdf>
<author>
<name>John Hsu</name>
<email>hsu@osrfoundation.org</email>
</author>
<description>
A cordless drill..
</description>
</model>

View 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>

View File

@ -3,8 +3,9 @@
<model>
<name>Cordless Drill</name>
<version>1.0</version>
<sdf version="1.2">model.sdf</sdf>
<sdf version="1.2">model-1_2.sdf</sdf>
<sdf version="1.3">model-1_3.sdf</sdf>
<sdf version="1.4">model.sdf</sdf>
<author>
<name>John Hsu</name>

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.4">
<model name="drill">
<link name="link">
<inertial>
@ -21,6 +21,13 @@
<uri>model://cordless_drill/meshes/cordless_drill.stl</uri>
</mesh>
</geometry>
<surface>
<contact>
<ode>
<max_vel>0.1</max_vel>
</ode>
</contact>
</surface>
</collision>
<visual name="visual">
<pose>0 0 -0.09 0 0 0</pose>
@ -32,4 +39,4 @@
</visual>
</link>
</model>
</gazebo>
</sdf>

View File

@ -1,20 +0,0 @@
<?xml version="1.0"?>
<model>
<name>iRobot Create</name>
<version>1.0</version>
<sdf version="1.2">model.sdf</sdf>
<sdf version="1.3">model-1_3.sdf</sdf>
<author>
<name>Nate Koenig</name>
<email>nate@osrfoundation.org</email>
</author>
<description>
A model of the iRobot Create.
</description>
<depend>
</depend>
</model>

296
create/model-1_2.sdf Normal file
View File

@ -0,0 +1,296 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<model name="create">
<link name="base">
<inertial>
<pose>0.001453 -0.000453 0.029787 0 0 0</pose>
<inertia>
<ixx>0.058640</ixx>
<ixy>0.000124</ixy>
<ixz>0.000615</ixz>
<iyy>0.058786</iyy>
<iyz>0.000014</iyz>
<izz>1.532440</izz>
</inertia>
<mass>2.234000</mass>
</inertial>
<collision name="base_collision">
<pose>0 0 0.047800 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.016495</radius>
<length>0.061163</length>
</cylinder>
</geometry>
</collision>
<visual name="base_visual">
<pose>0 0 0.047800 0 0 0</pose>
<geometry>
<mesh>
<uri>model://create/meshes/create_body.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="front_wheel_collision">
<pose>0.130000 0 0.017000 0 1.570700 1.570700</pose>
<geometry>
<sphere>
<radius>0.018000</radius>
</sphere>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name="front_wheel_visual">
<pose>0.130000 0 0.017000 0 1.570700 1.570700</pose>
<geometry>
<sphere>
<radius>0.009000</radius>
</sphere>
</geometry>
</visual>
<collision name="rear_wheel_collision">
<pose>-0.13 0 0.017 0 1.5707 1.5707</pose>
<geometry>
<sphere>
<radius>0.015000</radius>
</sphere>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name="rear_wheel_visual">
<pose>-0.130000 0 0.017000 0 1.570700 1.570700</pose>
<geometry>
<sphere>
<radius>0.007500</radius>
</sphere>
</geometry>
</visual>
<sensor name="left_cliff_sensor" type="ray">
<pose>0.070000 0.140000 0.027000 0 1.570790 0</pose>
<ray>
<scan>
<horizontal>
<samples>1</samples>
<resolution>1.000000</resolution>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</horizontal>
</scan>
<range>
<min>0.010000</min>
<max>0.040000</max>
<resolution>0.100000</resolution>
</range>
</ray>
</sensor>
<sensor name="leftfront_cliff_sensor" type="ray">
<pose>0.150000 0.040000 0.027000 0 1.570790 0</pose>
<ray>
<scan>
<horizontal>
<samples>1</samples>
<resolution>1.000000</resolution>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</horizontal>
</scan>
<range>
<min>0.010000</min>
<max>0.040000</max>
<resolution>0.100000</resolution>
</range>
</ray>
</sensor>
<sensor name="right_cliff_sensor" type="ray">
<pose>0.070000 -0.140000 0.027000 0 1.570790 0</pose>
<ray>
<scan>
<horizontal>
<samples>1</samples>
<resolution>1.000000</resolution>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</horizontal>
</scan>
<range>
<min>0.010000</min>
<max>0.040000</max>
<resolution>0.100000</resolution>
</range>
</ray>
</sensor>
<sensor name="rightfront_cliff_sensor" type="ray">
<pose>0.150000 -0.040000 0.027000 0 1.570790 0</pose>
<ray>
<scan>
<horizontal>
<samples>1</samples>
<resolution>1.000000</resolution>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</horizontal>
</scan>
<range>
<min>0.010000</min>
<max>0.040000</max>
<resolution>0.100000</resolution>
</range>
</ray>
</sensor>
<sensor name="wall_sensor" type="ray">
<pose>0.090000 -0.120000 0.059000 0 0 -1.000000</pose>
<ray>
<scan>
<horizontal>
<samples>1</samples>
<resolution>1.000000</resolution>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</horizontal>
</scan>
<range>
<min>0.016000</min>
<max>0.040000</max>
<resolution>0.100000</resolution>
</range>
</ray>
</sensor>
</link>
<link name="left_wheel">
<pose>0 0.130000 0.032000 0 0 0</pose>
<inertial>
<inertia>
<ixx>0.001000</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.001000</iyy>
<iyz>0</iyz>
<izz>0.001000</izz>
</inertia>
<mass>0.010000</mass>
</inertial>
<collision name="collision">
<pose>0 0 0 0 1.570700 1.570700</pose>
<geometry>
<cylinder>
<radius>0.033000</radius>
<length>0.023000</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>10</mu>
<mu2>10</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name="visual">
<pose>0 0 0 0 1.570700 1.570700</pose>
<geometry>
<cylinder>
<radius>0.033000</radius>
<length>0.023000</length>
</cylinder>
</geometry>
</visual>
</link>
<link name="right_wheel">
<pose>0 -0.130000 0.032000 0 0 0</pose>
<inertial>
<inertia>
<ixx>0.001000</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.001000</iyy>
<iyz>0</iyz>
<izz>0.001000</izz>
</inertia>
<mass>0.010000</mass>
</inertial>
<collision name="collision">
<pose>0 0 0 0 1.570700 1.570700</pose>
<geometry>
<cylinder>
<radius>0.033000</radius>
<length>0.023000</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>10</mu>
<mu2>10</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name="visual">
<pose>0 0 0 0 1.570700 1.570700</pose>
<geometry>
<cylinder>
<radius>0.033000</radius>
<length>0.023000</length>
</cylinder>
</geometry>
</visual>
</link>
<joint name="left_wheel" type="revolute">
<parent>base</parent>
<child>left_wheel</child>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<joint name="right_wheel" type="revolute">
<parent>base</parent>
<child>right_wheel</child>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
</model>
</gazebo>

View File

@ -3,8 +3,9 @@
<model>
<name>iRobot Create</name>
<version>1.0</version>
<sdf version="1.2">model.sdf</sdf>
<sdf version="1.2">model-1_2.sdf</sdf>
<sdf version="1.3">model-1_3.sdf</sdf>
<sdf version="1.4">model.sdf</sdf>
<author>
<name>Nate Koenig</name>

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.4">
<model name="create">
<link name="base">
@ -293,4 +293,4 @@
</joint>
</model>
</gazebo>
</sdf>

View File

@ -1,17 +0,0 @@
<?xml version="1.0"?>
<model>
<name>Cube 20k</name>
<version>1.0</version>
<sdf version="1.2">model.sdf</sdf>
<sdf version="1.3">model-1_3.sdf</sdf>
<author>
<name>Mihai Dhola</name>
<email>mihai@</email>
</author>
<description>
A cube composed of 20,000 triangles. This is used for testing.
</description>
</model>

24
cube_20k/model-1_2.sdf Normal file
View File

@ -0,0 +1,24 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<model name="cube_20k">
<link name="link">
<pose>0 0 0.5 0 0 0</pose>
<collision name="collision">
<geometry>
<mesh>
<uri>model://cube_20k/meshes/cube_20k.stl</uri>
<scale>0.5 0.5 0.5</scale>
</mesh>
</geometry>
</collision>
<visual name="visual">
<geometry>
<mesh>
<uri>model://cube_20k/meshes/cube_20k.stl</uri>
<scale>0.5 0.5 0.5</scale>
</mesh>
</geometry>
</visual>
</link>
</model>
</gazebo>

View File

@ -3,8 +3,9 @@
<model>
<name>Cube 20k</name>
<version>1.0</version>
<sdf version="1.2">model.sdf</sdf>
<sdf version="1.2">model-1_2.sdf</sdf>
<sdf version="1.3">model-1_3.sdf</sdf>
<sdf version="1.4">model.sdf</sdf>
<author>
<name>Mihai Dhola</name>

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.4">
<model name="cube_20k">
<link name="link">
<pose>0 0 0.5 0 0 0</pose>
@ -21,4 +21,4 @@
</visual>
</link>
</model>
</gazebo>
</sdf>

View File

@ -4,6 +4,7 @@
<name>Double pendulum with base</name>
<version>1.0</version>
<sdf version="1.3">model-1_3.sdf</sdf>
<sdf version="1.4">model.sdf</sdf>
<author>
<name>Steve Peters</name>

View File

@ -0,0 +1,204 @@
<?xml version='1.0'?>
<sdf version="1.4">
<model name="double_pendulum_with_base">
<link name="base">
<inertial>
<mass>100</mass>
</inertial>
<visual name="vis_plate_on_ground">
<pose>0 0 0.01 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.8</radius>
<length>0.02</length>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<visual name="vis_pole">
<pose>-0.275 0 1.1 0 0 0</pose>
<geometry>
<box><size>0.2 0.2 2.2</size></box>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<collision name="col_plate_on_ground">
<pose>0 0 0.01 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.8</radius>
<length>0.02</length>
</cylinder>
</geometry>
</collision>
<collision name="col_pole">
<pose>-0.275 0 1.1 0 0 0</pose>
<geometry>
<box><size>0.2 0.2 2.2</size></box>
</geometry>
</collision>
</link>
<!-- upper link, length 1, IC -90 degrees -->
<link name="upper_link">
<pose>0 0 2.1 -1.5708 0 0</pose>
<self_collide>0</self_collide>
<inertial>
<pose>0 0 0.5 0 0 0</pose>
</inertial>
<visual name="vis_upper_joint">
<pose>-0.05 0 0 0 1.5708 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.3</length>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<visual name="vis_lower_joint">
<pose>0 0 1.0 0 1.5708 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.2</length>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<visual name="vis_cylinder">
<pose>0 0 0.5 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.9</length>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<collision name="col_upper_joint">
<pose>-0.05 0 0 0 1.5708 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.3</length>
</cylinder>
</geometry>
</collision>
<collision name="col_lower_joint">
<pose>0 0 1.0 0 1.5708 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.2</length>
</cylinder>
</geometry>
</collision>
<collision name="col_cylinder">
<pose>0 0 0.5 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.9</length>
</cylinder>
</geometry>
</collision>
</link>
<!-- lower link, length 1, IC ~-120 degrees more -->
<link name="lower_link">
<pose>0.25 1.0 2.1 -2 0 0</pose>
<self_collide>0</self_collide>
<inertial>
<pose>0 0 0.5 0 0 0</pose>
</inertial>
<visual name="vis_lower_joint">
<pose>0 0 0 0 1.5708 0</pose>
<geometry>
<cylinder>
<radius>0.08</radius>
<length>0.3</length>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<visual name="vis_cylinder">
<pose>0 0 0.5 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.9</length>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<collision name="col_lower_joint">
<pose>0 0 0 0 1.5708 0</pose>
<geometry>
<cylinder>
<radius>0.08</radius>
<length>0.3</length>
</cylinder>
</geometry>
</collision>
<collision name="col_cylinder">
<pose>0 0 0.5 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.9</length>
</cylinder>
</geometry>
</collision>
</link>
<!-- pin joint for upper link, at origin of upper link -->
<joint name="upper_joint" type="revolute">
<parent>base</parent>
<child>upper_link</child>
<axis>
<xyz>1.0 0 0</xyz>
</axis>
</joint>
<!-- pin joint for lower link, at origin of child link -->
<joint name="lower_joint" type="revolute">
<parent>upper_link</parent>
<child>lower_link</child>
<axis>
<xyz>1.0 0 0</xyz>
</axis>
</joint>
</model>
</sdf>

View File

@ -1,22 +0,0 @@
<?xml version="1.0"?>
<model>
<name>Dumpster</name>
<version>1.0</version>
<sdf version="1.3">model-1_3.sdf</sdf>
<author>
<name>Cole Biesemeyer</name>
<email>cole.bsmr@gmail.com</email>
</author>
<author>
<name>Nate Koenig</name>
<email>natekoenig@gmail.com</email>
</author>
<description>
A dumpster.
</description>
</model>

View File

@ -4,6 +4,7 @@
<name>Dumpster</name>
<version>1.0</version>
<sdf version="1.3">model-1_3.sdf</sdf>
<sdf version="1.4">model.sdf</sdf>
<author>
<name>Cole Biesemeyer</name>

28
dumpster/model.sdf Normal file
View File

@ -0,0 +1,28 @@
<?xml version="1.0"?>
<sdf version="1.4">
<model name="Dumpster">
<link name="link">
<collision name="collision">
<geometry>
<mesh>
<uri>model://dumpster/meshes/dumpster.dae</uri>
</mesh>
</geometry>
</collision>
<visual name="visual">
<geometry>
<mesh>
<uri>model://dumpster/meshes/dumpster.dae</uri>
</mesh>
</geometry>
<material>
<script>
<uri>model://dumpster/materials/scripts</uri>
<uri>model://dumpster/materials/textures</uri>
<name>Dumpster/Diffuse</name>
</script>
</material>
</visual>
</link>
</model>
</sdf>

View File

@ -1,22 +0,0 @@
<?xml version="1.0"?>
<model>
<name>Fast Food</name>
<version>1.0</version>
<sdf version="1.3">model-1_3.sdf</sdf>
<author>
<name>Cole Biesemeyer</name>
<email>cole.bsmr@gmail.com</email>
</author>
<author>
<name>Nate Koenig</name>
<email>natekoenig@gmail.com</email>
</author>
<description>
A model of a fast food restaurant.
</description>
</model>

View File

@ -4,6 +4,7 @@
<name>Fast Food</name>
<version>1.0</version>
<sdf version="1.3">model-1_3.sdf</sdf>
<sdf version="1.4">model.sdf</sdf>
<author>
<name>Cole Biesemeyer</name>

30
fast_food/model.sdf Normal file
View File

@ -0,0 +1,30 @@
<?xml version="1.0"?>
<sdf version="1.4">
<model name="Fast Food">
<static>true</static>
<link name="link">
<pose>0 0 0 0 0 0</pose>
<collision name="collision">
<geometry>
<mesh>
<uri>model://fast_food/meshes/fast_food.dae</uri>
</mesh>
</geometry>
</collision>
<visual name="visual">
<geometry>
<mesh>
<uri>model://fast_food/meshes/fast_food.dae</uri>
</mesh>
</geometry>
<material>
<script>
<uri>model://fast_food/materials/scripts</uri>
<uri>model://fast_food/materials/textures</uri>
<name>FastFood/Diffuse</name>
</script>
</material>
</visual>
</link>
</model>
</sdf>

View File

@ -1,13 +0,0 @@
<?xml version='1.0'?>
<model>
<name>Fire hose (damping test)</name>
<version>0.1.0</version>
<sdf>model.sdf</sdf>
<author>
<name>John Hsu</name>
<email>hsu@osrfoundation.org</email>
</author>
<description>
This model approximates a fire hose.
</description>
</model>

2010
fire_hose_long/model-1_3.sdf Normal file

File diff suppressed because it is too large Load Diff

View File

@ -1,9 +1,10 @@
<?xml version='1.0'?>
<model>
<name>Fire hose (damping test)</name>
<version>0.1.0</version>
<sdf>model.sdf</sdf>
<sdf version='1.3'>model-1_3.sdf</sdf>
<sdf version='1.4'>model.sdf</sdf>
<author>
<name>John Hsu</name>
<email>hsu@osrfoundation.org</email>

File diff suppressed because it is too large Load Diff

View File

@ -1,22 +0,0 @@
<?xml version="1.0"?>
<model>
<name>Gas Station</name>
<version>1.0</version>
<sdf version="1.3">model-1_3.sdf</sdf>
<author>
<name>Cole Biesemeyer</name>
<email>cole.bsmr@gmail.com</email>
</author>
<author>
<name>Nate Koenig</name>
<email>natekoenig@gmail.com</email>
</author>
<description>
A model of a gas station.
</description>
</model>

View File

@ -4,6 +4,7 @@
<name>Gas Station</name>
<version>1.0</version>
<sdf version="1.3">model-1_3.sdf</sdf>
<sdf version="1.4">model.sdf</sdf>
<author>
<name>Cole Biesemeyer</name>

33
gas_station/model.sdf Normal file
View File

@ -0,0 +1,33 @@
<?xml version="1.0"?>
<sdf version="1.4">
<model name="Gas Station">
<static>true</static>
<link name="link">
<pose>0 0 0 0 0 0</pose>
<collision name="collision">
<geometry>
<mesh>
<uri>model://gas_station/meshes/gas_station.dae</uri>
</mesh>
</geometry>
</collision>
<visual name="visual">
<geometry>
<mesh>
<uri>model://gas_station/meshes/gas_station.dae</uri>
</mesh>
</geometry>
<material>
<script>
<uri>model://gas_station/materials/scripts</uri>
<uri>model://gas_station/materials/textures</uri>
<name>GasStation/Diffuse</name>
</script>
<shader type="normal_map_object_space">
<normal_map>GasStation_Normal.tga</normal_map>
</shader>
</material>
</visual>
</link>
</model>
</sdf>

View File

@ -1,17 +0,0 @@
<?xml version="1.0"?>
<model>
<name>Ground Plane</name>
<version>1.0</version>
<sdf version="1.2">model.sdf</sdf>
<sdf version="1.3">model-1_3.sdf</sdf>
<author>
<name>Nate Koenig</name>
<email>nate@osrfoundation.org</email>
</author>
<description>
A simple ground plane.
</description>
</model>

View File

@ -0,0 +1,39 @@
<?xml version="1.0"?>
<gazebo version="1.2">
<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<surface>
<friction>
<ode>
<mu>100</mu>
<mu2>50</mu2>
</ode>
</friction>
</surface>
</collision>
<visual name="visual">
<cast_shadows>false</cast_shadows>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
</model>
</gazebo>

View File

@ -3,8 +3,9 @@
<model>
<name>Ground Plane</name>
<version>1.0</version>
<sdf version="1.2">model.sdf</sdf>
<sdf version="1.2">model-1_2.sdf</sdf>
<sdf version="1.3">model-1_3.sdf</sdf>
<sdf version="1.4">model.sdf</sdf>
<author>
<name>Nate Koenig</name>

View File

@ -1,5 +1,5 @@
<?xml version="1.0"?>
<gazebo version="1.2">
<sdf version="1.4">
<model name="ground_plane">
<static>true</static>
<link name="link">
@ -36,4 +36,4 @@
</visual>
</link>
</model>
</gazebo>
</sdf>

View File

@ -1,17 +0,0 @@
<?xml version="1.0"?>
<model>
<name>Hammer</name>
<version>1.0</version>
<sdf version="1.2">model.sdf</sdf>
<sdf version="1.3">model-1_3.sdf</sdf>
<author>
<name>Nate Koenig</name>
<email>nate@osrfoundation.org</email>
</author>
<description>
A hammer.
</description>
</model>

44
hammer/model-1_2.sdf Normal file
View File

@ -0,0 +1,44 @@
<?xml version="1.0"?>
<gazebo version="1.2">
<model name="hammer">
<static>true</static>
<link name="link">
<!--
<pose>0 0 0 0 0 0</pose>
<collision name="shaft">
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.3</length>
</cylinder>
</geomtry>
</collision>
<collision name="head">
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.3</length>
</cylinder>
</geomtry>
</collision>
-->
<collision name="collision">
<geometry>
<mesh>
<uri>model://hammer/meshes/hammer.dae</uri>
</mesh>
</geometry>
</collision>
<visual name="visual">
<geometry>
<mesh>
<uri>model://hammer/meshes/hammer.dae</uri>
</mesh>
</geometry>
</visual>
</link>
</model>
</gazebo>

View File

@ -3,8 +3,9 @@
<model>
<name>Hammer</name>
<version>1.0</version>
<sdf version="1.2">model.sdf</sdf>
<sdf version="1.2">model-1_2.sdf</sdf>
<sdf version="1.3">model-1_3.sdf</sdf>
<sdf version="1.4">model.sdf</sdf>
<author>
<name>Nate Koenig</name>

View File

@ -1,5 +1,5 @@
<?xml version="1.0"?>
<gazebo version="1.2">
<sdf version="1.4">
<model name="hammer">
<static>true</static>
<link name="link">
@ -41,4 +41,4 @@
</visual>
</link>
</model>
</gazebo>
</sdf>

View File

@ -1,17 +0,0 @@
<?xml version="1.0"?>
<model>
<name>Hokuyo</name>
<version>1.0</version>
<sdf version="1.2">model.sdf</sdf>
<sdf version="1.3">model-1_3.sdf</sdf>
<author>
<name>John Hsu</name>
<email>hsu@osrfoundation.org</email>
</author>
<description>
Hokuyo model
</description>
</model>

File diff suppressed because one or more lines are too long

41
hokuyo/model-1_2.sdf Normal file
View File

@ -0,0 +1,41 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<model name="hokuyo">
<link name="link">
<gravity>false</gravity>
<inertial>
<mass>0.1</mass>
</inertial>
<visual name="visual">
<geometry>
<mesh>
<uri>model://hokuyo/meshes/hokuyo.dae</uri>
</mesh>
</geometry>
</visual>
<sensor name="laser" type="ray">
<pose>0.01 0 0.03 0 -0 0</pose>
<ray>
<scan>
<horizontal>
<samples>640</samples>
<resolution>1</resolution>
<min_angle>-2.26889</min_angle>
<max_angle>2.268899</max_angle>
</horizontal>
</scan>
<range>
<min>0.08</min>
<max>10</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin name="laser" filename="libRayPlugin.so" />
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>true</visualize>
</sensor>
</link>
</model>
</gazebo>

View File

@ -3,8 +3,9 @@
<model>
<name>Hokuyo</name>
<version>1.0</version>
<sdf version="1.2">model.sdf</sdf>
<sdf version="1.2">model-1_2.sdf</sdf>
<sdf version="1.3">model-1_3.sdf</sdf>
<sdf version="1.4">model.sdf</sdf>
<author>
<name>John Hsu</name>

View File

@ -1,8 +1,8 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.4">
<model name="hokuyo">
<pose>0 0 0.035 0 0 0</pose>
<link name="link">
<gravity>false</gravity>
<inertial>
<mass>0.1</mass>
</inertial>
@ -13,8 +13,29 @@
</mesh>
</geometry>
</visual>
<collision name="collision-base">
<pose>0 0 -0.0145 0 0 0</pose>
<geometry>
<box>
<size>0.05 0.05 0.041</size>
</box>
</geometry>
</collision>
<collision name="collision-top">
<pose>0 0 0.0205 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.021</radius>
<length>0.029</length>
</cylinder>
</geometry>
</collision>
<sensor name="laser" type="ray">
<pose>0.01 0 0.03 0 -0 0</pose>
<pose>0.01 0 0.0175 0 -0 0</pose>
<ray>
<scan>
<horizontal>
@ -38,4 +59,4 @@
</sensor>
</link>
</model>
</gazebo>
</sdf>

View File

@ -1,22 +0,0 @@
<?xml version="1.0"?>
<model>
<name>House 1</name>
<version>1.0</version>
<sdf version="1.3">model-1_3.sdf</sdf>
<author>
<name>Cole Biesemeyer</name>
<email>cole.bsmr@gmail.com</email>
</author>
<author>
<name>Nate Koenig</name>
<email>natekoenig@gmail.com</email>
</author>
<description>
A model of a residential house.
</description>
</model>

View File

@ -4,6 +4,7 @@
<name>House 1</name>
<version>1.0</version>
<sdf version="1.3">model-1_3.sdf</sdf>
<sdf version="1.4">model-1_4.sdf</sdf>
<author>
<name>Cole Biesemeyer</name>

32
house_1/model.sdf Normal file
View File

@ -0,0 +1,32 @@
<?xml version="1.0"?>
<sdf version="1.4">
<model name="House 1">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<mesh>
<uri>model://house_1/meshes/house_1.dae</uri>
</mesh>
</geometry>
</collision>
<visual name="visual">
<geometry>
<mesh>
<uri>model://house_1/meshes/house_1.dae</uri>
</mesh>
</geometry>
<material>
<script>
<uri>model://house_1/materials/scripts</uri>
<uri>model://house_1/materials/textures</uri>
<name>House_1/Diffuse</name>
</script>
<shader type="normal_map_object_space">
<normal_map>House_1_Normal.tga</normal_map>
</shader>
</material>
</visual>
</link>
</model>
</sdf>

View File

@ -1,22 +0,0 @@
<?xml version="1.0"?>
<model>
<name>House 2</name>
<version>1.0</version>
<sdf version="1.3">model-1_3.sdf</sdf>
<author>
<name>Cole Biesemeyer</name>
<email>cole.bsmr@gmail.com</email>
</author>
<author>
<name>Nate Koenig</name>
<email>natekoenig@gmail.com</email>
</author>
<description>
A model of a residential house.
</description>
</model>

View File

@ -4,6 +4,7 @@
<name>House 2</name>
<version>1.0</version>
<sdf version="1.3">model-1_3.sdf</sdf>
<sdf version="1.4">model.sdf</sdf>
<author>
<name>Cole Biesemeyer</name>

29
house_2/model.sdf Normal file
View File

@ -0,0 +1,29 @@
<?xml version="1.0"?>
<sdf version="1.4">
<model name="House 2">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<mesh>
<uri>model://house_2/meshes/house_2.dae</uri>
</mesh>
</geometry>
</collision>
<visual name="visual">
<geometry>
<mesh>
<uri>model://house_2/meshes/house_2.dae</uri>
</mesh>
</geometry>
<material>
<script>
<uri>model://house_2/materials/scripts</uri>
<uri>model://house_2/materials/textures</uri>
<name>House_2/Diffuse</name>
</script>
</material>
</visual>
</link>
</model>
</sdf>

View File

@ -1,22 +0,0 @@
<?xml version="1.0"?>
<model>
<name>House 3</name>
<version>1.0</version>
<sdf version="1.3">model-1_3.sdf</sdf>
<author>
<name>Cole Biesemeyer</name>
<email>cole.bsmr@gmail.com</email>
</author>
<author>
<name>Nate Koenig</name>
<email>natekoenig@gmail.com</email>
</author>
<description>
A model of a residential house.
</description>
</model>

View File

@ -4,6 +4,7 @@
<name>House 3</name>
<version>1.0</version>
<sdf version="1.3">model-1_3.sdf</sdf>
<sdf version="1.4">model.sdf</sdf>
<author>
<name>Cole Biesemeyer</name>

29
house_3/model.sdf Normal file
View File

@ -0,0 +1,29 @@
<?xml version="1.0"?>
<sdf version="1.4">
<model name="House 3">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<mesh>
<uri>model://house_3/meshes/house_3.dae</uri>
</mesh>
</geometry>
</collision>
<visual name="visual">
<geometry>
<mesh>
<uri>model://house_3/meshes/house_3.dae</uri>
</mesh>
</geometry>
<material>
<script>
<uri>model://house_3/materials/scripts</uri>
<uri>model://house_3/materials/textures</uri>
<name>House_3/Diffuse</name>
</script>
</material>
</visual>
</link>
</model>
</sdf>

341
husky/husky-1_3.sdf Normal file
View File

@ -0,0 +1,341 @@
<?xml version='1.0'?>
<sdf version="1.3">
<model name="husky">
<pose>0 0 .5 0 0 0</pose>
<!-- Main Chassis -->
<link name="base_link">
<!-- Physics -->
<collision name='collision'>
<!-- <pose>0 0 -0.3 0 0 0</pose> -->
<pose>0 0 0.1 0 0 0</pose>
<geometry>
<box>
<size>1.0074 0.5709 0.2675</size>
</box>
</geometry>
</collision>
<inertial>
<mass>33.855</mass>
<pose>-0.0856132 -0.000839955 0.238145</pose>
<inertia>
<ixx>2.2343</ixx>
<ixy>-0.023642</ixy>
<ixz>0.275174</ixz>
<iyy>3.42518</iyy>
<iyz>0.00239624</iyz>
<izz>2.1241</izz>
</inertia>
</inertial>
<!-- Visual -->
<!-- Base frame -->
<visual name='base'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh><uri>model://husky/meshes/base_link.stl</uri></mesh>
</geometry>
<material>
<script>
<name>Gazebo/FlatBlack</name>
</script>
</material>
</visual>
<!-- Top Plate -->
<visual name='top_plate'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh><uri>model://husky/meshes/top_plate.stl</uri></mesh>
</geometry>
<material>
<script>
<name>Gazebo/Yellow</name>
</script>
</material>
</visual>
<!-- Front Bumper -->
<visual name='front_bumper'>
<pose>0.47 0 0.091 0 0 0</pose>
<geometry>
<mesh><uri>model://husky/meshes/bumper.stl</uri></mesh>
</geometry>
<material>
<script>
<name>Gazebo/FlatBlack</name>
</script>
</material>
</visual>
<!-- Rear Bumper -->
<visual name='rear_bumper'>
<pose>-0.47 0 0.091 0 0 3.141</pose>
<geometry>
<mesh><uri>model://husky/meshes/bumper.stl</uri></mesh>
</geometry>
<material>
<script>
<name>Gazebo/FlatBlack</name>
</script>
</material>
</visual>
<!-- User Rail -->
<visual name='user_rail'>
<pose>0.272 0 0.245 0 0 0</pose>
<geometry>
<mesh><uri>model://husky/meshes/user_rail.stl</uri></mesh>
</geometry>
<material>
<script>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
<!-- Back Left Wheel -->
<link name='back_left_wheel'>
<pose>-0.256 0.285475 0.035 0 0 0</pose>
<inertial>
<mass>2.6357</mass>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>0.0246688</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0246688</iyy>
<iyz>0</iyz>
<izz>0.0441058</izz>
</inertia>
</inertial>
<collision name='back_left_wheel_collision'>
<pose>0 0 0 -1.5707 0 0</pose>
<geometry>
<cylinder>
<radius>0.17775</radius>
<length>0.1143</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>100000.0</mu>
<mu2>100000.0</mu2>
<slip1>0.0</slip1>
<slip2>0.0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name='back_left_wheel'>
<pose>0 0 0 -3.14159 0 0</pose>
<geometry>
<mesh><uri>model://husky/meshes/wheel.stl</uri></mesh>
</geometry>
<material>
<script>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
<joint name='back_left_joint' type='revolute'>
<parent>base_link</parent>
<child>back_left_wheel</child>
<axis>
<xyz>0 1 0</xyz>
</axis>
<physics><ode><limit>
<cfm>0.000000</cfm>
<erp>0.900000</erp>
</limit></ode></physics>
</joint>
<!-- Back Right Wheel -->
<link name='back_right_wheel'>
<pose>-0.256 -0.285475 0.035 0 0 0</pose>
<inertial>
<mass>2.6357</mass>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>0.0246688</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0246688</iyy>
<iyz>0</iyz>
<izz>0.0441058</izz>
</inertia>
</inertial>
<collision name='back_right_wheel_collision'>
<pose>0 0 0 -1.5707 0 0</pose>
<geometry>
<cylinder>
<radius>0.17775</radius>
<length>0.1143</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>100000.0</mu>
<mu2>100000.0</mu2>
<slip1>0.0</slip1>
<slip2>0.0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name='back_right_wheel'>
<pose>0 0 0 -3.14159 0 0</pose>
<geometry>
<mesh><uri>model://husky/meshes/wheel.stl</uri></mesh>
</geometry>
<material>
<script>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
<joint name='back_right_joint' type='revolute'>
<parent>base_link</parent>
<child>back_right_wheel</child>
<axis>
<xyz>0 1 0</xyz>
</axis>
<physics><ode><limit>
<cfm>0.000000</cfm>
<erp>0.900000</erp>
</limit></ode></physics>
</joint>
<!-- Front Left Wheel -->
<link name='front_left_wheel'>
<pose>0.256 0.285475 0.035 0 0 0</pose>
<inertial>
<mass>2.6357</mass>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>0.0246688</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0246688</iyy>
<iyz>0</iyz>
<izz>0.0441058</izz>
</inertia>
</inertial>
<collision name='front_left_wheel_collision'>
<pose>0 0 0 -1.5707 0 0</pose>
<geometry>
<cylinder>
<radius>0.17775</radius>
<length>0.1143</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>100000.0</mu>
<mu2>100000.0</mu2>
<slip1>0.0</slip1>
<slip2>0.0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name='front_left_wheel'>
<pose>0 0 0 -3.14159 0 0</pose>
<geometry>
<mesh><uri>model://husky/meshes/wheel.stl</uri></mesh>
</geometry>
<material>
<script>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
<joint name='front_left_joint' type='revolute'>
<parent>base_link</parent>
<child>front_left_wheel</child>
<axis>
<xyz>0 1 0</xyz>
</axis>
<physics><ode><limit>
<cfm>0.000000</cfm>
<erp>0.900000</erp>
</limit></ode></physics>
</joint>
<!-- Front Right Wheel -->
<link name='front_right_wheel'>
<pose>0.256 -0.285475 0.035 0 0 0</pose>
<inertial>
<mass>2.6357</mass>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>0.0246688</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0246688</iyy>
<iyz>0</iyz>
<izz>0.0441058</izz>
</inertia>
</inertial>
<collision name='front_right_wheel_collision'>
<pose>0 0 0 -1.5707 0 0</pose>
<geometry>
<cylinder>
<radius>0.17775</radius>
<length>0.1143</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>100000.0</mu>
<mu2>100000.0</mu2>
<slip1>0.0</slip1>
<slip2>0.0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name='front_right_wheel'>
<pose>0 0 0 -3.14159 0 0</pose>
<geometry>
<mesh><uri>model://husky/meshes/wheel.stl</uri></mesh>
</geometry>
<material>
<script>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
<joint name='front_right_joint' type='revolute'>
<parent>base_link</parent>
<child>front_right_wheel</child>
<axis>
<xyz>0 1 0</xyz>
</axis>
<physics><ode><limit>
<cfm>0.000000</cfm>
<erp>0.900000</erp>
</limit></ode></physics>
</joint>
<plugin name="husky_diff_controller" filename="libhusky_gazebo_plugins.so">
<alwaysOn>true</alwaysOn>
<updateRate>100.0</updateRate>
<backLeftJoint>back_left_joint</backLeftJoint>
<backRightJoint>back_right_joint</backRightJoint>
<frontLeftJoint>front_left_joint</frontLeftJoint>
<frontRightJoint>front_right_joint</frontRightJoint>
<wheelSeparation>0.5709</wheelSeparation>
<wheelDiameter>0.3555</wheelDiameter>
<torque>35</torque>
</plugin>
</model>
</sdf>

341
husky/husky.sdf Normal file
View File

@ -0,0 +1,341 @@
<?xml version='1.0'?>
<sdf version="1.4">
<model name="husky">
<pose>0 0 .5 0 0 0</pose>
<!-- Main Chassis -->
<link name="base_link">
<!-- Physics -->
<collision name='collision'>
<!-- <pose>0 0 -0.3 0 0 0</pose> -->
<pose>0 0 0.1 0 0 0</pose>
<geometry>
<box>
<size>1.0074 0.5709 0.2675</size>
</box>
</geometry>
</collision>
<inertial>
<mass>33.855</mass>
<pose>-0.0856132 -0.000839955 0.238145</pose>
<inertia>
<ixx>2.2343</ixx>
<ixy>-0.023642</ixy>
<ixz>0.275174</ixz>
<iyy>3.42518</iyy>
<iyz>0.00239624</iyz>
<izz>2.1241</izz>
</inertia>
</inertial>
<!-- Visual -->
<!-- Base frame -->
<visual name='base'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh><uri>model://husky/meshes/base_link.stl</uri></mesh>
</geometry>
<material>
<script>
<name>Gazebo/FlatBlack</name>
</script>
</material>
</visual>
<!-- Top Plate -->
<visual name='top_plate'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh><uri>model://husky/meshes/top_plate.stl</uri></mesh>
</geometry>
<material>
<script>
<name>Gazebo/Yellow</name>
</script>
</material>
</visual>
<!-- Front Bumper -->
<visual name='front_bumper'>
<pose>0.47 0 0.091 0 0 0</pose>
<geometry>
<mesh><uri>model://husky/meshes/bumper.stl</uri></mesh>
</geometry>
<material>
<script>
<name>Gazebo/FlatBlack</name>
</script>
</material>
</visual>
<!-- Rear Bumper -->
<visual name='rear_bumper'>
<pose>-0.47 0 0.091 0 0 3.141</pose>
<geometry>
<mesh><uri>model://husky/meshes/bumper.stl</uri></mesh>
</geometry>
<material>
<script>
<name>Gazebo/FlatBlack</name>
</script>
</material>
</visual>
<!-- User Rail -->
<visual name='user_rail'>
<pose>0.272 0 0.245 0 0 0</pose>
<geometry>
<mesh><uri>model://husky/meshes/user_rail.stl</uri></mesh>
</geometry>
<material>
<script>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
<!-- Back Left Wheel -->
<link name='back_left_wheel'>
<pose>-0.256 0.285475 0.035 0 0 0</pose>
<inertial>
<mass>2.6357</mass>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>0.0246688</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0246688</iyy>
<iyz>0</iyz>
<izz>0.0441058</izz>
</inertia>
</inertial>
<collision name='back_left_wheel_collision'>
<pose>0 0 0 -1.5707 0 0</pose>
<geometry>
<cylinder>
<radius>0.17775</radius>
<length>0.1143</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>100000.0</mu>
<mu2>100000.0</mu2>
<slip1>0.0</slip1>
<slip2>0.0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name='back_left_wheel'>
<pose>0 0 0 -3.14159 0 0</pose>
<geometry>
<mesh><uri>model://husky/meshes/wheel.stl</uri></mesh>
</geometry>
<material>
<script>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
<joint name='back_left_joint' type='revolute'>
<parent>base_link</parent>
<child>back_left_wheel</child>
<axis>
<xyz>0 1 0</xyz>
</axis>
<physics><ode><limit>
<cfm>0.000000</cfm>
<erp>0.900000</erp>
</limit></ode></physics>
</joint>
<!-- Back Right Wheel -->
<link name='back_right_wheel'>
<pose>-0.256 -0.285475 0.035 0 0 0</pose>
<inertial>
<mass>2.6357</mass>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>0.0246688</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0246688</iyy>
<iyz>0</iyz>
<izz>0.0441058</izz>
</inertia>
</inertial>
<collision name='back_right_wheel_collision'>
<pose>0 0 0 -1.5707 0 0</pose>
<geometry>
<cylinder>
<radius>0.17775</radius>
<length>0.1143</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>100000.0</mu>
<mu2>100000.0</mu2>
<slip1>0.0</slip1>
<slip2>0.0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name='back_right_wheel'>
<pose>0 0 0 -3.14159 0 0</pose>
<geometry>
<mesh><uri>model://husky/meshes/wheel.stl</uri></mesh>
</geometry>
<material>
<script>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
<joint name='back_right_joint' type='revolute'>
<parent>base_link</parent>
<child>back_right_wheel</child>
<axis>
<xyz>0 1 0</xyz>
</axis>
<physics><ode><limit>
<cfm>0.000000</cfm>
<erp>0.900000</erp>
</limit></ode></physics>
</joint>
<!-- Front Left Wheel -->
<link name='front_left_wheel'>
<pose>0.256 0.285475 0.035 0 0 0</pose>
<inertial>
<mass>2.6357</mass>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>0.0246688</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0246688</iyy>
<iyz>0</iyz>
<izz>0.0441058</izz>
</inertia>
</inertial>
<collision name='front_left_wheel_collision'>
<pose>0 0 0 -1.5707 0 0</pose>
<geometry>
<cylinder>
<radius>0.17775</radius>
<length>0.1143</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>100000.0</mu>
<mu2>100000.0</mu2>
<slip1>0.0</slip1>
<slip2>0.0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name='front_left_wheel'>
<pose>0 0 0 -3.14159 0 0</pose>
<geometry>
<mesh><uri>model://husky/meshes/wheel.stl</uri></mesh>
</geometry>
<material>
<script>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
<joint name='front_left_joint' type='revolute'>
<parent>base_link</parent>
<child>front_left_wheel</child>
<axis>
<xyz>0 1 0</xyz>
</axis>
<physics><ode><limit>
<cfm>0.000000</cfm>
<erp>0.900000</erp>
</limit></ode></physics>
</joint>
<!-- Front Right Wheel -->
<link name='front_right_wheel'>
<pose>0.256 -0.285475 0.035 0 0 0</pose>
<inertial>
<mass>2.6357</mass>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>0.0246688</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0246688</iyy>
<iyz>0</iyz>
<izz>0.0441058</izz>
</inertia>
</inertial>
<collision name='front_right_wheel_collision'>
<pose>0 0 0 -1.5707 0 0</pose>
<geometry>
<cylinder>
<radius>0.17775</radius>
<length>0.1143</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>100000.0</mu>
<mu2>100000.0</mu2>
<slip1>0.0</slip1>
<slip2>0.0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name='front_right_wheel'>
<pose>0 0 0 -3.14159 0 0</pose>
<geometry>
<mesh><uri>model://husky/meshes/wheel.stl</uri></mesh>
</geometry>
<material>
<script>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
<joint name='front_right_joint' type='revolute'>
<parent>base_link</parent>
<child>front_right_wheel</child>
<axis>
<xyz>0 1 0</xyz>
</axis>
<physics><ode><limit>
<cfm>0.000000</cfm>
<erp>0.900000</erp>
</limit></ode></physics>
</joint>
<plugin name="husky_diff_controller" filename="libhusky_gazebo_plugins.so">
<alwaysOn>true</alwaysOn>
<updateRate>100.0</updateRate>
<backLeftJoint>back_left_joint</backLeftJoint>
<backRightJoint>back_right_joint</backRightJoint>
<frontLeftJoint>front_left_joint</frontLeftJoint>
<frontRightJoint>front_right_joint</frontRightJoint>
<wheelSeparation>0.5709</wheelSeparation>
<wheelDiameter>0.3555</wheelDiameter>
<torque>35</torque>
</plugin>
</model>
</sdf>

BIN
husky/meshes/base_link.stl Executable file

Binary file not shown.

BIN
husky/meshes/bumper.stl Executable file

Binary file not shown.

BIN
husky/meshes/top_plate.stl Executable file

Binary file not shown.

BIN
husky/meshes/user_rail.stl Executable file

Binary file not shown.

BIN
husky/meshes/wheel.stl Executable file

Binary file not shown.

16
husky/model.config Normal file
View File

@ -0,0 +1,16 @@
<?xml version='1.0'?>
<model>
<name>Clearpath Robotics Husky A200</name>
<version>1.0</version>
<sdf version="1.3">husky-1_3.sdf</sdf>
<sdf version="1.4">husky.sdf</sdf>
<author>
<name>Ryan Gariepy</name>
<email>rgariepy@clearpathrobotics.com</email>
</author>
<description>
Clearpath Robotics Husky A200 - Base Model
</description>
</model>

View File

@ -1,14 +0,0 @@
<?xml version='1.0'?>
<model>
<name>iRobot Hand</name>
<version>0.1.0</version>
<sdf version='1.3'>model-1_3.sdf</sdf>
<author>
<name>OSRF</name>
<email>hsu@osrfoundation.org</email>
</author>
<description>
iRobot hand model.
</description>
</model>

View File

@ -3,6 +3,7 @@
<name>iRobot Hand</name>
<version>0.1.0</version>
<sdf version='1.3'>model-1_3.sdf</sdf>
<sdf version='1.4'>model.sdf</sdf>
<author>
<name>OSRF</name>

2561
irobot_hand/model.sdf Normal file

File diff suppressed because it is too large Load Diff

View File

@ -1,17 +0,0 @@
<?xml version="1.0"?>
<model>
<version>1.0</version>
<name>Kinect</name>
<sdf version="1.2">model.sdf</sdf>
<sdf version="1.3">model-1_3.sdf</sdf>
<author>
<name>Nate Koenig</name>
<email>nate@osrfoundation.org</email>
</author>
<description>
A model of the kinect sensor
</description>
</model>

42
kinect/model-1_2.sdf Normal file
View File

@ -0,0 +1,42 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<model name="kinect">
<pose>0 0 0.036 0 0 0</pose>
<link name="link">
<inertial>
<mass>0.1</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.073000 0.276000 0.072000</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<mesh>
<uri>model://kinect/meshes/kinect.dae</uri>
</mesh>
</geometry>
</visual>
<sensor name="camera" type="depth">
<update_rate>20</update_rate>
<camera>
<horizontal_fov>1.047198</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.05</near>
<far>3</far>
</clip>
</camera>
</sensor>
</link>
</model>
</gazebo>

View File

@ -21,7 +21,6 @@
</mesh>
</geometry>
</visual>
<sensor name="camera" type="depth">
<update_rate>20</update_rate>
<camera>

View File

@ -3,8 +3,9 @@
<model>
<version>1.0</version>
<name>Kinect</name>
<sdf version="1.2">model.sdf</sdf>
<sdf version="1.2">model-1_2.sdf</sdf>
<sdf version="1.3">model-1_3.sdf</sdf>
<sdf version="1.4">model.sdf</sdf>
<author>
<name>Nate Koenig</name>

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.4">
<model name="kinect">
<pose>0 0 0.036 0 0 0</pose>
<link name="link">
@ -21,7 +21,6 @@
</mesh>
</geometry>
</visual>
<sensor name="camera" type="depth">
<update_rate>20</update_rate>
<camera>
@ -39,4 +38,4 @@
</sensor>
</link>
</model>
</gazebo>
</sdf>

View File

@ -0,0 +1,15 @@
<?xml version="1.0"?>
<sdf version="1.3">
<model name="Kitchen Dining">
<static>true</static>
<link name="link">
<visual name="visual">
<geometry>
<mesh>
<uri>model://kitchen_dining/meshes/kitchen_dining.dae</uri>
</mesh>
</geometry>
</visual>
</link>
</model>
</sdf>

View File

@ -3,7 +3,8 @@
<model>
<name>Kitchen and Dining</name>
<version>1.0</version>
<sdf version="1.3">model.sdf</sdf>
<sdf version="1.3">model-1_3.sdf</sdf>
<sdf version="1.4">model.sdf</sdf>
<author>
<name>Nate Koenig</name>

View File

@ -1,5 +1,5 @@
<?xml version="1.0"?>
<sdf version="1.3">
<sdf version="1.4">
<model name="Kitchen Dining">
<static>true</static>
<link name="link">

22
lamp_post/model-1_3.sdf Normal file
View File

@ -0,0 +1,22 @@
<?xml version="1.0"?>
<sdf version="1.3">
<model name="Lamp Post">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<mesh>
<uri>model://lamp_post/meshes/lamp_post.dae</uri>
</mesh>
</geometry>
</collision>
<visual name="visual">
<geometry>
<mesh>
<uri>model://lamp_post/meshes/lamp_post.dae</uri>
</mesh>
</geometry>
</visual>
</link>
</model>
</sdf>

View File

@ -3,7 +3,8 @@
<model>
<name>Lamp Post</name>
<version>1.0</version>
<sdf version="1.3">model.sdf</sdf>
<sdf version="1.3">model-1_3.sdf</sdf>
<sdf version="1.4">model.sdf</sdf>
<author>
<name>Cole Biesemeyer</name>

View File

@ -1,5 +1,5 @@
<?xml version="1.0"?>
<sdf version="1.3">
<sdf version="1.4">
<model name="Lamp Post">
<static>true</static>
<link name="link">

View File

@ -1,22 +0,0 @@
<?xml version="1.0"?>
<model>
<name>Mailbox</name>
<version>1.0</version>
<sdf version="1.3">model-1_3.sdf</sdf>
<author>
<name>Cole Biesemeyer</name>
<email>cole.bsmr@gmail.com</email>
</author>
<author>
<name>Nate Koenig</name>
<email>natekoenig@gmail.com</email>
</author>
<description>
A mailbox.
</description>
</model>

View File

@ -4,6 +4,7 @@
<name>Mailbox</name>
<version>1.0</version>
<sdf version="1.3">model-1_3.sdf</sdf>
<sdf version="1.4">model.sdf</sdf>
<author>
<name>Cole Biesemeyer</name>

Some files were not shown because too many files have changed in this diff Show More