This commit is contained in:
Nate Koenig 2012-10-01 18:14:38 -07:00
commit 410ad182d2
61 changed files with 15374 additions and 69 deletions

View File

@ -34,13 +34,17 @@ set (dirs
camera
create
ground_plane
hammer
hokuyo
kinect
monkey_wrench
pioneer2dx
pr2
powerplant
simple_arm
sun
turtlebot
utility_cart
willowgarage
youbot
)

View File

@ -10,7 +10,7 @@
</contributor>
<created>2011-04-04T13:58:47.183927</created>
<modified>2011-04-04T13:58:47.183946</modified>
<unit meter="0.01" name="centimeter"/>
<unit meter="1.0" name="meter"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_effects>

View File

@ -7,7 +7,7 @@
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
<size>500 500</size>
</plane>
</geometry>
<surface>
@ -24,7 +24,7 @@
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
<size>500 500</size>
</plane>
</geometry>
<material>

16
hammer/manifest.xml Normal file
View File

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

Binary file not shown.

After

Width:  |  Height:  |  Size: 66 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 66 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 66 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 66 KiB

326
hammer/meshes/hammer.dae Normal file

File diff suppressed because one or more lines are too long

44
hammer/model.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

@ -8,18 +8,8 @@
</model>
<model>
<name>Turtle Bot</name>
<uri>/turtlebot</uri>
</model>
<model>
<name>Willow Garage</name>
<uri>/willowgarage</uri>
</model>
<model>
<name>Kinect</name>
<uri>/kinect</uri>
<name>Hammer</name>
<uri>/hammer</uri>
</model>
<model>
@ -27,14 +17,29 @@
<uri>/hokuyo</uri>
</model>
<model>
<name>Keuka YouBot</name>
<uri>/youbot</uri>
</model>
<model>
<name>Kinect</name>
<uri>/kinect</uri>
</model>
<model>
<name>Monkey Wrench</name>
<uri>/monkey_wrench</uri>
</model>
<model>
<name>Pioneer2 DX</name>
<uri>/pioneer2dx</uri>
</model>
<model>
<name>Simple Arm</name>
<uri>/simple_arm</uri>
<name>Power Plant</name>
<uri>/powerplant</uri>
</model>
<model>
@ -43,8 +48,23 @@
</model>
<model>
<name>Keuka YouBot</name>
<uri>/youbot</uri>
<name>Simple Arm</name>
<uri>/simple_arm</uri>
</model>
<model>
<name>Turtle Bot</name>
<uri>/turtlebot</uri>
</model>
<model>
<name>Utility Cart</name>
<uri>/utility_cart</uri>
</model>
<model>
<name>Willow Garage</name>
<uri>/willowgarage</uri>
</model>
</models>

View File

@ -0,0 +1,16 @@
<?xml version="1.0"?>
<model>
<name>Monkey Wrench</name>
<version>1.0</version>
<sdf>model.sdf</sdf>
</model>
<author>
<name>Nate Koenig</name>
<email>nate@osrfoundation.org</email>
</author>
<description>
A monkey wrench.
</description>

File diff suppressed because one or more lines are too long

46
monkey_wrench/model.sdf Normal file
View File

@ -0,0 +1,46 @@
<?xml version="1.0"?>
<gazebo version='1.2'>
<model name="monkey wrench">
<static>false</static>
<link name="link">
<pose>0 0 0 0 0 0</pose>
<!--
<collision name="shaft">
<pose>0 0 0 0 0 0</pose>
<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://monkey_wrench/meshes/monkey_wrench.dae</uri>
</mesh>
</geometry>
</collision>
<visual name="visual">
<geometry>
<mesh>
<uri>model://monkey_wrench/meshes/monkey_wrench.dae</uri>
</mesh>
</geometry>
</visual>
</link>
</model>
</gazebo>

View File

@ -10,7 +10,7 @@
</contributor>
<created>2011-12-06T15:18:22.492696</created>
<modified>2011-12-06T15:18:22.492709</modified>
<unit meter="0.01" name="centimeter"/>
<unit meter="1.00" name="meter"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_effects>

View File

@ -10,7 +10,7 @@
</contributor>
<created>2011-12-06T15:23:13.027427</created>
<modified>2011-12-06T15:23:13.027441</modified>
<unit meter="0.01" name="centimeter"/>
<unit meter="1.00" name="meter"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_effects>
@ -256,4 +256,4 @@
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>
</COLLADA>

View File

@ -47,7 +47,10 @@
</sphere>
</geometry>
<material>
<script>Gazebo/FlatBlack</script>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/FlatBlack</name>
</script>
</material>
</visual>
</link>
@ -82,7 +85,10 @@
</cylinder>
</geometry>
<material>
<script>Gazebo/FlatBlack</script>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/FlatBlack</name>
</script>
</material>
</visual>
</link>
@ -117,7 +123,10 @@
</cylinder>
</geometry>
<material>
<script>Gazebo/FlatBlack</script>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/FlatBlack</name>
</script>
</material>
</visual>
</link>

17
powerplant/manifest.xml Normal file
View File

@ -0,0 +1,17 @@
<?xml version="1.0"?>
<model>
<name>Power Plant</name>
<version>1.0</version>
<license></license>
<sdf>model.sdf</sdf>
</model>
<author>
<name>Nate Koenig</name>
<email>nate@osrfoundation.org</email>
</author>
<description>
A power plant.
</description>

Binary file not shown.

After

Width:  |  Height:  |  Size: 49 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 5.5 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 9.8 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 9.9 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 11 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 66 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 11 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 16 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 8.0 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 38 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 75 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 17 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 7.8 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 73 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 6.7 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 76 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 87 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 38 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 4.5 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 7.9 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 5.8 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 15 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 2.1 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 2.1 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 134 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 5.9 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 19 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 18 KiB

File diff suppressed because one or more lines are too long

34
powerplant/model.sdf Normal file
View File

@ -0,0 +1,34 @@
<?xml version="1.0"?>
<gazebo version='1.2'>
<model name="powerplant">
<static>true</static>
<link name="link">
<pose>0 0 0.01 0 0 0</pose>
<collision name="wall1">
<geometry>
<mesh>
<uri>model://powerplant/meshes/powerplant.dae</uri>
</mesh>
</geometry>
</collision>
<visual name="visual1">
<geometry>
<mesh>
<uri>model://powerplant/meshes/powerplant.dae</uri>
</mesh>
</geometry>
</visual>
</link>
<!--
<link name="door1">
<pose>8 -42.5 0 0 0 0</pose>
<collision>
</collision>
</link>
-->
</model>
</gazebo>

View File

@ -1,3 +1,4 @@
<?xml version="1.0" ?>
<gazebo version='1.2'>
<model name='pr2'>
<static>0</static>

View File

@ -30,7 +30,7 @@
</box>
</geometry>
<material>
<script>Gazebo/Blue</script>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Blue</name></script>
</material>
</visual>
<collision name="arm_base_geom_arm_trunk">
@ -51,7 +51,7 @@
</cylinder>
</geometry>
<material>
<script>Gazebo/Red</script>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Red</name></script>
</material>
</visual>
</link>
@ -87,7 +87,7 @@
</cylinder>
</geometry>
<material>
<script>Gazebo/Yellow</script>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Yellow</name></script>
</material>
</visual>
<collision name="arm_shoulder_pan_geom_arm_shoulder">
@ -106,7 +106,7 @@
</box>
</geometry>
<material>
<script>Gazebo/Yellow</script>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Yellow</name></script>
</material>
</visual>
</link>
@ -142,7 +142,7 @@
</cylinder>
</geometry>
<material>
<script>Gazebo/Red</script>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Red</name></script>
</material>
</visual>
<collision name="arm_elbow_pan_geom_arm_elbow">
@ -161,7 +161,7 @@
</box>
</geometry>
<material>
<script>Gazebo/Yellow</script>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Yellow</name></script>
</material>
</visual>
<collision name="arm_elbow_pan_geom_arm_wrist">
@ -182,7 +182,7 @@
</cylinder>
</geometry>
<material>
<script>Gazebo/Red</script>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Red</name></script>
</material>
</visual>
</link>
@ -218,7 +218,7 @@
</cylinder>
</geometry>
<material>
<script>Gazebo/Yellow</script>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Yellow</name></script>
</material>
</visual>
</link>
@ -254,7 +254,7 @@
</cylinder>
</geometry>
<material>
<script>Gazebo/Red</script>
<script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Red</name></script>
</material>
</visual>
</link>

16
utility_cart/manifest.xml Normal file
View File

@ -0,0 +1,16 @@
<?xml version="1.0"?>
<model>
<name>Utility Cart</name>
<version>1.0</version>
<sdf>model.sdf</sdf>
</model>
<author>
<name>John Hsu</name>
<email>hsu@osrfoundation.org</email>
</author>
<description>
A utility cart.
</description>

213
utility_cart/model.sdf Normal file
View File

@ -0,0 +1,213 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<model name="car" static="false">
<link name="chassis">
<pose>0 0 0.3 0 0 0</pose>
<collision name="collision">
<geometry>
<box><size>2.0 1.0 0.2</size></box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box><size>2.0 1.0 0.2</size></box>
</geometry>
<material><script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Green</name></script></material>
</visual>
</link>
<link name="front_left_wheel">
<pose>0.8 0.6 0.3 0 1.5707 1.5707</pose>
<collision name="collision">
<geometry>
<cylinder><radius>0.3</radius><length>0.1</length></cylinder>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder><radius>0.3</radius><length>0.1</length></cylinder>
</geometry>
<material><script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Black</name></script></material>
</visual>
</link>
<link name="front_right_wheel">
<pose>0.8 -0.6 0.3 0 1.5707 1.5707</pose>
<collision name="collision">
<geometry>
<cylinder><radius>0.3</radius><length>0.1</length></cylinder>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder><radius>0.3</radius><length>0.1</length></cylinder>
</geometry>
<material><script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Black</name></script></material>
</visual>
</link>
<link name="back_right_wheel">
<pose>-0.8 -0.6 0.3 0 1.5707 1.5707</pose>
<collision name="collision">
<geometry>
<cylinder><radius>0.3</radius><length>0.1</length></cylinder>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder><radius>0.3</radius><length>0.1</length></cylinder>
</geometry>
<material><script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Black</name></script></material>
</visual>
</link>
<link name="back_left_wheel">
<pose>-0.8 0.6 0.3 0 1.5707 1.5707</pose>
<collision name="collision">
<geometry>
<cylinder><radius>0.3</radius><length>0.1</length></cylinder>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder><radius>0.3</radius><length>0.1</length></cylinder>
</geometry>
<material><script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Black</name></script></material>
</visual>
</link>
<link name="gas_pedal">
<pose>0.3 0.1 0.5 0 0 0</pose>
<collision name="collision">
<geometry>
<box><size>0.1 0.1 0.1</size></box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box><size>0.1 0.1 0.1</size></box>
</geometry>
<material><script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Red</name></script></material>
</visual>
</link>
<link name="brake_pedal">
<pose>0.3 0.25 0.5 0 0 0</pose>
<collision name="collision">
<geometry>
<box><size>0.1 0.1 0.1</size></box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box><size>0.1 0.1 0.1</size></box>
</geometry>
<material><script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Blue</name></script></material>
</visual>
</link>
<link name="steering_wheel">
<pose>0.3 0.2 1.0 0 1.5707 0</pose>
<collision name="collision">
<geometry>
<cylinder><radius>0.1</radius><length>0.01</length></cylinder>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder><radius>0.1</radius><length>0.01</length></cylinder>
</geometry>
<material><script><uri>file://media/materials/scripts/gazebo.material</uri><name>Gazebo/Blue</name></script></material>
</visual>
</link>
<joint type="prismatic" name="gas_joint">
<parent>chassis</parent>
<child>gas_pedal</child>
<axis xyz="1 0 0">
<limit lower="0" upper="0.2" />
</axis>
</joint>
<joint type="prismatic" name="brake_joint">
<parent>chassis</parent>
<child>brake_pedal</child>
<axis xyz="1 0 0">
<limit lower="0" upper="0.2" />
</axis>
</joint>
<joint type="revolute" name="steering_joint">
<parent>chassis</parent>
<child>steering_wheel</child>
<axis xyz="1 0 0">
<limit lower="-7.853" upper="7.853" />
</axis>
</joint>
<joint type="revolute2" name="front_left_joint">
<parent>chassis</parent>
<child>front_left_wheel</child>
<axis xyz="0 0 1">
<limit lower="0" upper="0" />
</axis>
<axis2 xyz="0 1 0" />
<physics>
<ode>
<limit cfm="0.0" erp="0.9" />
</ode>
</physics>
</joint>
<joint type="revolute2" name="front_right_joint">
<parent>chassis</parent>
<child>front_right_wheel</child>
<axis xyz="0 0 1">
<limit lower="0" upper="0" />
</axis>
<axis2 xyz="0 1 0" />
<physics>
<ode>
<limit cfm="0.0" erp="0.9" />
</ode>
</physics>
</joint>
<joint type="revolute2" name="back_right_joint">
<parent>chassis</parent>
<child>back_right_wheel</child>
<axis xyz="0 0 1">
<limit lower="0" upper="0" />
</axis>
<axis2 xyz="0 1 0" />
<physics>
<ode>
<limit cfm="0.0" erp="0.9" />
</ode>
</physics>
</joint>
<joint type="revolute2" name="back_left_joint">
<parent>chassis</parent>
<child>back_left_wheel</child>
<axis xyz="0 0 1">
<limit lower="0" upper="0" />
</axis>
<axis2 xyz="0 1 0" />
<physics>
<ode>
<limit cfm="0.0" erp="0.9" />
</ode>
</physics>
</joint>
<plugin filename="libVehiclePlugin.so" name="vehicle">
<!-- Joints for each wheel -->
<front_left>front_left_joint</front_left>
<front_right>front_right_joint</front_right>
<back_left>back_left_joint</back_left>
<back_right>back_right_joint</back_right>
<!-- Joint which controls the gas -->
<gas>gas_joint</gas>
<!-- Joint which controls the gas -->
<brake>brake_joint</brake>
<!-- Joint which controls the steering -->
<steering>steering_joint</steering>
<!-- Power is multiplied by "gas" to determine force applied to wheels -->
<front_power>10</front_power>
<rear_power>10</rear_power>
<!-- The angle range the front tires can turn for steering, in radians -->
<tire_angle_range>0.5</tire_angle_range>
<!-- Maximum speed for the car in meters/second -->
<max_speed>10</max_speed>
<!-- Factor for the down-force applied as the car travels faster -->
<!-- A larger number increases the down force -->
<aero_load>0.1</aero_load>
</plugin>
</model>
</gazebo>

View File

@ -10,7 +10,7 @@
</contributor>
<created>2011-03-30T16:40:02.202948</created>
<modified>2011-03-30T16:40:02.202992</modified>
<unit meter="0.01" name="centimeter"/>
<unit meter="1.0" name="meter"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_effects>

View File

@ -10,7 +10,7 @@
</contributor>
<created>2011-03-30T16:40:51.721701</created>
<modified>2011-03-30T16:40:51.721717</modified>
<unit meter="0.01" name="centimeter"/>
<unit meter="1.0" name="meter"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_effects>

View File

@ -10,7 +10,7 @@
</contributor>
<created>2011-03-30T16:42:14.736197</created>
<modified>2011-03-30T16:42:14.736208</modified>
<unit meter="0.01" name="centimeter"/>
<unit meter="1.0" name="meter"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_effects>

View File

@ -10,7 +10,7 @@
</contributor>
<created>2011-04-01T15:41:10.733377</created>
<modified>2011-04-01T15:41:10.733388</modified>
<unit meter="0.01" name="centimeter"/>
<unit meter="1.0" name="meter"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_effects>

View File

@ -10,7 +10,7 @@
</contributor>
<created>2011-03-30T16:43:22.192947</created>
<modified>2011-03-30T16:43:22.192965</modified>
<unit meter="0.01" name="centimeter"/>
<unit meter="1.0" name="meter"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_effects>

View File

@ -10,7 +10,7 @@
</contributor>
<created>2011-03-30T16:44:15.058801</created>
<modified>2011-03-30T16:44:15.058815</modified>
<unit meter="0.01" name="centimeter"/>
<unit meter="1.0" name="meter"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_effects>

View File

@ -10,7 +10,7 @@
</contributor>
<created>2011-02-15T14:49:35.513908</created>
<modified>2011-02-15T14:49:35.513941</modified>
<unit meter="0.01" name="centimeter"/>
<unit meter="1.0" name="meter"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_effects>
@ -368,4 +368,4 @@
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>
</COLLADA>

View File

@ -10,7 +10,7 @@
</contributor>
<created>2011-02-15T14:52:26.738894</created>
<modified>2011-02-15T14:52:26.738910</modified>
<unit meter="0.01" name="centimeter"/>
<unit meter="1.0" name="meter"/>
<up_axis>Z_UP</up_axis>
</asset>
<library_effects>
@ -358,4 +358,4 @@
<scene>
<instance_visual_scene url="#Scene"/>
</scene>
</COLLADA>
</COLLADA>

View File

@ -81,7 +81,6 @@
<geometry>
<mesh>
<uri>model://youbot/meshes/base/base_convex.stl</uri>
<scale>1.000000 1.000000 1</scale>
</mesh>
</geometry>
<surface>
@ -116,7 +115,6 @@
<geometry>
<mesh>
<uri>model://youbot/meshes/base/base.dae</uri>
<scale>1.000000 1.000000 1</scale>
</mesh>
</geometry>
</visual>
@ -143,7 +141,6 @@
<geometry>
<mesh>
<uri>model://youbot/meshes/arm/arm0_convex.stl</uri>
<scale>1.000000 1.000000 1</scale>
</mesh>
</geometry>
<surface>
@ -178,12 +175,11 @@
<geometry>
<mesh>
<uri>model://youbot/meshes/arm/arm0.dae</uri>
<scale>1.000000 1.000000 1</scale>
</mesh>
</geometry>
<material>
<script>
<uri>model://youbot/materials/youbot.material</uri>
<uri>model://youbot/materials/scripts/youbot.material</uri>
<name>youbot/DarkGrey</name>
</script>
</material>
@ -211,7 +207,6 @@
<geometry>
<mesh>
<uri>model://youbot/meshes/arm/arm1_convex.stl</uri>
<scale>1.000000 1.000000 1</scale>
</mesh>
</geometry>
<surface>
@ -246,7 +241,6 @@
<geometry>
<mesh>
<uri>model://youbot/meshes/arm/arm1.dae</uri>
<scale>1.000000 1.000000 1</scale>
</mesh>
</geometry>
</visual>
@ -273,7 +267,6 @@
<geometry>
<mesh>
<uri>model://youbot/meshes/arm/arm2_convex.stl</uri>
<scale>1.000000 1.000000 1</scale>
</mesh>
</geometry>
<surface>
@ -308,7 +301,6 @@
<geometry>
<mesh>
<uri>model://youbot/meshes/arm/arm2.dae</uri>
<scale>1.000000 1.000000 1</scale>
</mesh>
</geometry>
</visual>
@ -335,7 +327,6 @@
<geometry>
<mesh>
<uri>model://youbot/meshes/arm/arm3_convex.stl</uri>
<scale>1.000000 1.000000 1</scale>
</mesh>
</geometry>
<surface>
@ -370,7 +361,6 @@
<geometry>
<mesh>
<uri>model://youbot/meshes/arm/arm3.dae</uri>
<scale>1.000000 1.000000 1</scale>
</mesh>
</geometry>
</visual>
@ -397,7 +387,6 @@
<geometry>
<mesh>
<uri>model://youbot/meshes/arm/arm4_convex.stl</uri>
<scale>1.000000 1.000000 1</scale>
</mesh>
</geometry>
<surface>
@ -432,7 +421,6 @@
<geometry>
<mesh>
<uri>model://youbot/meshes/arm/arm4.dae</uri>
<scale>1.000000 1.000000 1</scale>
</mesh>
</geometry>
</visual>
@ -459,7 +447,6 @@
<geometry>
<mesh>
<uri>model://youbot/meshes/arm/arm5_convex.stl</uri>
<scale>1.000000 1.000000 1</scale>
</mesh>
</geometry>
<surface>
@ -494,7 +481,6 @@
<geometry>
<mesh>
<uri>model://youbot/meshes/arm/arm5.dae</uri>
<scale>1.000000 1.000000 1</scale>
</mesh>
</geometry>
</visual>
@ -521,7 +507,6 @@
<geometry>
<mesh>
<uri>model://youbot/meshes/gripper/palm_convex.stl</uri>
<scale>1.000000 1.000000 1</scale>
</mesh>
</geometry>
<surface>
@ -556,7 +541,6 @@
<geometry>
<mesh>
<uri>model://youbot/meshes/gripper/palm.stl</uri>
<scale>1.000000 1.000000 1</scale>
</mesh>
</geometry>
<material>
@ -589,7 +573,6 @@
<geometry>
<mesh>
<uri>model://youbot/meshes/gripper/finger_convex.stl</uri>
<scale>1.000000 1.000000 1</scale>
</mesh>
</geometry>
<surface>
@ -624,7 +607,6 @@
<geometry>
<mesh>
<uri>model://youbot/meshes/gripper/finger.stl</uri>
<scale>1.000000 1.000000 1</scale>
</mesh>
</geometry>
</visual>
@ -651,7 +633,6 @@
<geometry>
<mesh>
<uri>model://youbot/meshes/gripper/finger_convex.stl</uri>
<scale>1.000000 1.000000 1</scale>
</mesh>
</geometry>
<surface>
@ -686,7 +667,6 @@
<geometry>
<mesh>
<uri>model://youbot/meshes/gripper/finger.stl</uri>
<scale>1.000000 1.000000 1</scale>
</mesh>
</geometry>
</visual>
@ -713,7 +693,6 @@
<geometry>
<mesh>
<uri>model://hokuyo/meshes/hokuyo_convex.stl</uri>
<scale>1.000000 1.000000 1</scale>
</mesh>
</geometry>
<surface>
@ -748,7 +727,6 @@
<geometry>
<mesh>
<uri>model://hokuyo/meshes/hokuyo.dae</uri>
<scale>1.000000 1.000000 1</scale>
</mesh>
</geometry>
</visual>
@ -1136,7 +1114,6 @@
<geometry>
<mesh>
<uri>model://youbot/meshes/plate/plate_convex.stl</uri>
<scale>1.000000 1.000000 1</scale>
</mesh>
</geometry>
<surface>
@ -1171,7 +1148,6 @@
<geometry>
<mesh>
<uri>model://youbot/meshes/plate/plate.dae</uri>
<scale>1.000000 1.000000 1</scale>
</mesh>
</geometry>
</visual>