Updated model-1_3 sdf files

This commit is contained in:
Nate Koenig 2012-11-30 13:08:08 -08:00
parent d5d1cd1fd5
commit 99ae23da11
32 changed files with 59 additions and 59 deletions

View File

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

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.3">
<model name="camera">
<link name="link">
<pose>0.05 0.05 0.05 0 0 0</pose>
@ -31,4 +31,4 @@
</sensor>
</link>
</model>
</gazebo>
</sdf>

View File

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

View File

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

View File

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

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.3">
<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

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

View File

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

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.3">
<model name="hokuyo">
<link name="link">
<inertial>
@ -37,4 +37,4 @@
</sensor>
</link>
</model>
</gazebo>
</sdf>

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.3">
<model name="kinect">
<pose>0 0 0.036 0 0 0</pose>
<link name="link">
@ -39,4 +39,4 @@
</sensor>
</link>
</model>
</gazebo>
</sdf>

View File

@ -43,4 +43,4 @@
</visual>
</link>
</model>
</gazebo>
</sdf>

View File

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

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.3">
<model name="nist_fiducial_barrel">
<static>true</static>
<link name="nist_fiducial_barrel_link">
@ -22,4 +22,4 @@
</visual>
</link>
</model>
</gazebo>
</sdf>

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.3">
<model name="nist_maze_wall_120">
<static>true</static>
<link name="nist_maze_wall_120_link">
@ -22,4 +22,4 @@
</visual>
</link>
</model>
</gazebo>
</sdf>

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.3">
<model name="nist_maze_wall_240">
<static>true</static>
<link name="nist__maze_wall_240_link">
@ -22,4 +22,4 @@
</visual>
</link>
</model>
</gazebo>
</sdf>

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.3">
<model name="nist">
<static>true</static>
<link name="nist_maze_wall_triple_holes_120_link">
@ -22,4 +22,4 @@
</visual>
</link>
</model>
</gazebo>
</sdf>

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.3">
<model name="nist_simple_ramp_120">
<static>true</static>
<link name="nist_simple_ramp_120_link">
@ -22,4 +22,4 @@
</visual>
</link>
</model>
</gazebo>
</sdf>

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.3">
<model name="nist_stairs_120">
<static>true</static>
<link name="nist_stairs_120_link">
@ -22,4 +22,4 @@
</visual>
</link>
</model>
</gazebo>
</sdf>

View File

@ -1,5 +1,5 @@
<?xml version="1.0"?>
<gazebo version="1.2">
<sdf version="1.3">
<model name="pioneer2dx">
<link name="chassis">
<pose>0 0 0.16 0 0 0</pose>
@ -154,4 +154,4 @@
</plugin>
</model>
</gazebo>
</sdf>

View File

@ -31,4 +31,4 @@
-->
</model>
</gazebo>
</sdf>

View File

@ -3033,4 +3033,4 @@
</axis>
</joint>
</model>
</gazebo>
</sdf>

View File

@ -713,5 +713,5 @@
</joint>
<static>0</static>
</model>
</gazebo>
</sdf>
Success

View File

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

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.3">
<model name="simple_arm">
<link name="arm_base">
<inertial>
@ -306,4 +306,4 @@
</axis>
</joint>
</model>
</gazebo>
</sdf>

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.3">
<model name="simple_arm_gripper">
<include>
<uri>model://simple_arm</uri>
@ -24,4 +24,4 @@
</axis>
</joint>
</model>
</gazebo>
</sdf>

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.3">
<model name="simple_gripper">
<link name="riser">
<pose>-0.15 0.0 0.5 0 0 0</pose>
@ -245,4 +245,4 @@
<palm_link>palm</palm_link>
</gripper>
</model>
</gazebo>
</sdf>

View File

@ -16,4 +16,4 @@
<direction>-0.5 0.5 -1.0</direction>
</light>
</gazebo>
</sdf>

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.3">
<model name="table">
<static>false</static>
<link name="link">
@ -123,4 +123,4 @@
</visual>
</link>
</model>
</gazebo>
</sdf>

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.3">
<model name="turtlebot">
<link name="rack">
<inertial>
@ -471,4 +471,4 @@
</joint>
</model>
</gazebo>
</sdf>

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.3">
<model name="car">
<link name="chassis">
<pose>0 0 0.3 0 0 0</pose>
@ -266,4 +266,4 @@
<aero_load>0.1</aero_load>
</plugin>
</model>
</gazebo>
</sdf>

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.3">
<model name="willowgarage">
<static>true</static>
<pose>-20 -20 0 0 0 0</pose>
@ -21,4 +21,4 @@
</visual>
</link>
</model>
</gazebo>
</sdf>

View File

@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<sdf version="1.3">
<model name="youbot">
<pose>0 0 0.09 0 0 0</pose>
<link name="base_footprint">
@ -1416,4 +1416,4 @@
</joint>
<static>0</static>
</model>
</gazebo>
</sdf>