|
From: <hsu...@us...> - 2008-11-15 07:49:40
|
Revision: 6806
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=6806&view=rev
Author: hsujohnhsu
Date: 2008-11-15 07:49:30 +0000 (Sat, 15 Nov 2008)
Log Message:
-----------
rename robot.world to robot_simple.world
turn off lighting for robot_obstacle.world
Modified Paths:
--------------
pkg/trunk/demos/pr2_gazebo/pr2.launch
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_obstacle.world
Added Paths:
-----------
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_simple.world
Removed Paths:
-------------
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot.world
Modified: pkg/trunk/demos/pr2_gazebo/pr2.launch
===================================================================
--- pkg/trunk/demos/pr2_gazebo/pr2.launch 2008-11-15 07:46:31 UTC (rev 6805)
+++ pkg/trunk/demos/pr2_gazebo/pr2.launch 2008-11-15 07:49:30 UTC (rev 6806)
@@ -5,7 +5,7 @@
<include file="$(find wg_robot_description)/pr2/send_description.launch" />
<!-- start gazebo -->
- <node pkg="gazebo" type="gazebo" args="-n $(find gazebo_robot_description)/world/robot.world" respawn="false" output="screen">
+ <node pkg="gazebo" type="gazebo" args="-n $(find gazebo_robot_description)/world/robot_simple.world" respawn="false" output="screen">
<env name="LD_LIBRARY_PATH" value="$(find gazebo_plugin)/lib:$(find gazebo)/gazebo/lib:$(find Cg)/Cg/lib:$LD_LIBRARY_PATH" />
<env name="GAZEBO_RESOURCE_PATH" value="$(find gazebo_robot_description)/world" />
<env name="OGRE_RESOURCE_PATH" value="$(find ogre)/ogre/lib/OGRE" />
Deleted: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot.world 2008-11-15 07:46:31 UTC (rev 6805)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot.world 2008-11-15 07:49:30 UTC (rev 6806)
@@ -1,307 +0,0 @@
-<?xml version="1.0"?>
-
-<gazebo:world
- xmlns:xi="http://www.w3.org/2001/XInclude"
- xmlns:gazebo="http://playerstage.sourceforge.net/gazebo/xmlschema/#gz"
- xmlns:model="http://playerstage.sourceforge.net/gazebo/xmlschema/#model"
- xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
- xmlns:window="http://playerstage.sourceforge.net/gazebo/xmlschema/#window"
- xmlns:param="http://playerstage.sourceforge.net/gazebo/xmlschema/#param"
- xmlns:body="http://playerstage.sourceforge.net/gazebo/xmlschema/#body"
- xmlns:geo="http://willowgarage.com/xmlschema/#geo"
- xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom"
- xmlns:joint="http://playerstage.sourceforge.net/gazebo/xmlschema/#joint"
- xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
- xmlns:ui="http://playerstage.sourceforge.net/gazebo/xmlschema/#ui"
- xmlns:rendering="http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering"
- xmlns:renderable="http://playerstage.sourceforge.net/gazebo/xmlschema/#renderable"
- xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
- xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics" >
-
- <verbosity>5</verbosity>
-
-<!-- cfm is 1e-5 for single precision -->
-<!-- erp is typically .1-.8 -->
-<!-- here's the global contact cfm/erp -->
- <physics:ode>
- <stepTime>0.001</stepTime>
- <gravity>0 0 -9.8</gravity>
- <cfm>0.000000000001</cfm>
- <erp>0.2</erp>
- <quickStep>true</quickStep>
- <quickStepIters>3</quickStepIters>
- <quickStepW>1.3</quickStepW>
- <quickStepIters>3</quickStepIters>
- <quickStepW>1.3</quickStepW>
- </physics:ode>
-
- <geo:origin>
- <lat>37.4270909558</lat><lon>-122.077919338</lon>
- </geo:origin>
-
- <rendering:gui>
- <type>fltk</type>
- <size>1024 800</size>
- <pos>0 0</pos>
- <frames>
- <row height="100%">
- <camera width="100%">
- <xyz>0 0 20</xyz>
- <rpy>0 90 90</rpy>
- </camera>
- </row>
- </frames>
- </rendering:gui>
-
-
- <rendering:ogre>
- <ambient>1.0 1.0 1.0 1.0</ambient>
- <sky>
- <material>Gazebo/CloudySky</material>
- </sky>
- <gazeboPath>media</gazeboPath>
- <grid>false</grid>
- <maxUpdateRate>10</maxUpdateRate>
- </rendering:ogre>
-
-
- <model:physical name="gplane">
- <xyz>0 0 0</xyz>
- <rpy>0 0 0</rpy>
- <static>true</static>
-
- <body:plane name="plane">
- <geom:plane name="plane">
- <kp>1000000.0</kp>
- <kd>1.0</kd>
- <normal>0 0 1</normal>
- <size>51.3 51.3</size>
- <!-- map3.png -->
- <material>PR2/floor_texture</material>
- </geom:plane>
- </body:plane>
- </model:physical>
-
- <!--
- <model:empty name="ros_model">
- <body:empty name="ros_body">
- <controller:ros_node name="ros_node" plugin="libRos_Node.so">
- <nodeName>simulator_ros_node</nodeName>
- </controller:ros_node>
- </body:empty>
- </model:empty>
- -->
-
- <!-- The "desk"-->
- <!-- small desks -->
- <model:physical name="desk1_model">
- <xyz>2.28 -0.21 0</xyz>
- <rpy>0.0 0.0 0.0 </rpy>
- <include embedded="true">
- <!--xi:include href="desk6.model" /--> <!-- block legs -->
- <xi:include href="desk4.model" /> <!-- skinny pole legs -->
- </include>
- </model:physical>
-
- <!-- The second "desk"-->
- <model:physical name="desk2_model">
- <xyz>2.25 -3.0 0</xyz>
- <rpy>0.0 0.0 0.0 </rpy>
- <include embedded="true">
- <xi:include href="desk5.model" />
- </include>
- </model:physical>
-
- <!-- The small cylinder "cup" -->
- <model:physical name="cylinder1_model">
- <xyz> 2.5 0.0 1.5</xyz>
- <rpy> 0.0 0.0 0.0</rpy>
- <body:cylinder name="cylinder1_body">
- <geom:cylinder name="cylinder1_geom">
- <kp>100000000.0</kp>
- <kd>0.1</kd>
- <mesh>default</mesh>
- <size>0.025 0.075</size>
- <mass> 0.05</mass>
- <visual>
- <size> 0.05 0.05 0.075</size>
- <material>Gazebo/PioneerBody</material>
- <mesh>unit_cylinder</mesh>
- </visual>
- </geom:cylinder>
- <geom:box name="cylinder1_base_geom">
- <kp>100000000.0</kp>
- <kd>0.1</kd>
- <mesh>default</mesh>
- <xyz>0.0 0.0 -0.033</xyz>
- <size>0.05 0.05 0.01</size>
- <mass> 0.01</mass>
- <visual>
- <size> 0.05 0.05 0.01</size>
- <material>Gazebo/Fish</material>
- <mesh>unit_box</mesh>
- </visual>
- </geom:box>
- </body:cylinder>
- </model:physical>
-
- <!-- The small box "cup" -->
- <model:physical name="object1_model">
- <xyz> 0.835 -0.55 0.95</xyz>
- <rpy> 0.0 0.0 30.0</rpy>
- <body:box name="object1_body">
- <geom:box name="object1_geom">
- <kp>100000000.0</kp>
- <kd>0.1</kd>
- <mesh>default</mesh>
- <size>0.1 0.03 0.03</size>
- <mass> 0.05</mass>
- <visual>
- <size> 0.1 0.030 0.03</size>
- <material>Gazebo/PioneerBody</material>
- <mesh>unit_box</mesh>
- </visual>
- </geom:box>
- </body:box>
-
- <controller:P3D name="p3d_object_controller" plugin="libP3D.so">
- <updateRate>100.0</updateRate>
- <bodyName>object1_body</bodyName>
- <topicName>object1_body_ground_truth</topicName>
- <frameName>object1_body_ground_truth_frame</frameName>
- <interface:position name="p3d_object_position"/>
- </controller:P3D>
-
- </model:physical>
-
-
- <!-- The small ball -->
- <model:physical name="sphere1_model">
- <xyz> 2.5 -2.8 1.5</xyz>
- <rpy> 0.0 0.0 0.0</rpy>
- <body:sphere name="sphere1_body">
- <geom:sphere name="sphere1_geom">
- <kp>1000000.0</kp>
- <kd>1.0</kd>
- <mesh>default</mesh>
- <size> 0.15</size>
- <mass> 1.0</mass>
- <visual>
- <size> 0.3 0.3 0.3</size>
- <material>Gazebo/PioneerBody</material>
- <mesh>unit_sphere</mesh>
- </visual>
- </geom:sphere>
- </body:sphere>
- </model:physical>
-
- <!-- The large ball map3.png -->
- <model:physical name="sphere2_model">
- <xyz> 5.85 4.35 1.55</xyz>
- <rpy> 0.0 0.0 0.0</rpy>
- <body:sphere name="sphere2_body">
- <geom:sphere name="sphere2_geom">
- <kp>1000000.0</kp>
- <kd>1.0</kd>
- <mesh>default</mesh>
- <size> 1.0</size>
- <mass> 1.0</mass>
- <visual>
- <size> 2.0 2.0 2.0</size>
- <material>Gazebo/Rocky</material>
- <mesh>unit_sphere</mesh>
- </visual>
- </geom:sphere>
- </body:sphere>
- </model:physical>
-
- <!-- The wall in front map3.png -->
- <model:physical name="wall_2_model">
- <xyz> 11.6 -1.55 1.0</xyz>
- <rpy> 0.0 0.0 0.0</rpy>
- <static>true</static>
- <body:box name="wall_2_body">
- <geom:box name="wall_2_geom">
- <mesh>default</mesh>
- <size>2.1 32.8 2.0</size>
- <visual>
- <size>2.1 32.8 2.0</size>
- <material>Gazebo/PioneerBody</material>
- <mesh>unit_box</mesh>
- </visual>
- </geom:box>
- </body:box>
- </model:physical>
-
- <!-- The wall behind -->
- <model:physical name="wall_1_model">
- <xyz> -11.3 -1.45 1.0</xyz>
- <rpy> 0.0 0.0 0.0</rpy>
- <static>true</static>
- <body:box name="wall_1_body">
- <geom:box name="wall_1_geom">
- <mesh>default</mesh>
- <size>0.4 24.0 2.0</size>
- <visual>
- <size>0.4 24.0 2.0</size>
- <material>Gazebo/PioneerBody</material>
- <mesh>unit_box</mesh>
- </visual>
- </geom:box>
- </body:box>
- </model:physical>
-
- <!-- The wall 3 -->
- <model:physical name="wall_3_model">
- <xyz> 6.7 8.05 1.0</xyz>
- <rpy> 0.0 0.0 0.0</rpy>
- <static>true</static>
- <body:box name="wall_3_body">
- <geom:box name="wall_3_geom">
- <mesh>default</mesh>
- <size>7.5 1.2 2.0</size>
- <visual>
- <size>7.5 1.2 2.0</size>
- <material>Gazebo/Chrome</material>
- <mesh>unit_box</mesh>
- </visual>
- </geom:box>
- </body:box>
- </model:physical>
-
-
-
- <model:physical name="robot_model1">
-
- <controller:ros_time name="ros_time" plugin="libRos_Time.so">
- <alwaysOn>true</alwaysOn>
- <updateRate>1000.0</updateRate>
- <interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
- </controller:ros_time>
-
- <xyz>0.0 0.0 0.0408</xyz> <!-- bottom of base off the ground by this much, basically wheel height below skirt -->
- <rpy>0.0 0.0 0.0 </rpy>
-
- <!-- base, torso and arms -->
- <include embedded="true">
- <xi:include href="pr2.model" />
- </include>
-
- </model:physical>
-
-
- <!-- White Directional light -->
- <!--
- <model:renderable name="directional_white">
- <light>
- <type>directional</type>
- <direction>0 -0.5 -0.5</direction>
- <diffuseColor>0.4 0.4 0.4</diffuseColor>
- <specularColor>0.0 0.0 0.0</specularColor>
- <attenuation>1 0.0 1.0 0.4</attenuation>
- </light>
- </model:renderable>
- -->
-
-
-</gazebo:world>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_obstacle.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_obstacle.world 2008-11-15 07:46:31 UTC (rev 6805)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_obstacle.world 2008-11-15 07:49:30 UTC (rev 6806)
@@ -358,6 +358,7 @@
<!-- White Directional light -->
+ <!--
<model:renderable name="directional_white">
<light>
<type>directional</type>
@@ -367,6 +368,7 @@
<attenuation>1 0.0 1.0 0.4</attenuation>
</light>
</model:renderable>
+ -->
</gazebo:world>
Copied: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_simple.world (from rev 6805, pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot.world)
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_simple.world (rev 0)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_simple.world 2008-11-15 07:49:30 UTC (rev 6806)
@@ -0,0 +1,307 @@
+<?xml version="1.0"?>
+
+<gazebo:world
+ xmlns:xi="http://www.w3.org/2001/XInclude"
+ xmlns:gazebo="http://playerstage.sourceforge.net/gazebo/xmlschema/#gz"
+ xmlns:model="http://playerstage.sourceforge.net/gazebo/xmlschema/#model"
+ xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
+ xmlns:window="http://playerstage.sourceforge.net/gazebo/xmlschema/#window"
+ xmlns:param="http://playerstage.sourceforge.net/gazebo/xmlschema/#param"
+ xmlns:body="http://playerstage.sourceforge.net/gazebo/xmlschema/#body"
+ xmlns:geo="http://willowgarage.com/xmlschema/#geo"
+ xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom"
+ xmlns:joint="http://playerstage.sourceforge.net/gazebo/xmlschema/#joint"
+ xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
+ xmlns:ui="http://playerstage.sourceforge.net/gazebo/xmlschema/#ui"
+ xmlns:rendering="http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering"
+ xmlns:renderable="http://playerstage.sourceforge.net/gazebo/xmlschema/#renderable"
+ xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
+ xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics" >
+
+ <verbosity>5</verbosity>
+
+<!-- cfm is 1e-5 for single precision -->
+<!-- erp is typically .1-.8 -->
+<!-- here's the global contact cfm/erp -->
+ <physics:ode>
+ <stepTime>0.001</stepTime>
+ <gravity>0 0 -9.8</gravity>
+ <cfm>0.000000000001</cfm>
+ <erp>0.2</erp>
+ <quickStep>true</quickStep>
+ <quickStepIters>3</quickStepIters>
+ <quickStepW>1.3</quickStepW>
+ <quickStepIters>3</quickStepIters>
+ <quickStepW>1.3</quickStepW>
+ </physics:ode>
+
+ <geo:origin>
+ <lat>37.4270909558</lat><lon>-122.077919338</lon>
+ </geo:origin>
+
+ <rendering:gui>
+ <type>fltk</type>
+ <size>1024 800</size>
+ <pos>0 0</pos>
+ <frames>
+ <row height="100%">
+ <camera width="100%">
+ <xyz>0 0 20</xyz>
+ <rpy>0 90 90</rpy>
+ </camera>
+ </row>
+ </frames>
+ </rendering:gui>
+
+
+ <rendering:ogre>
+ <ambient>1.0 1.0 1.0 1.0</ambient>
+ <sky>
+ <material>Gazebo/CloudySky</material>
+ </sky>
+ <gazeboPath>media</gazeboPath>
+ <grid>false</grid>
+ <maxUpdateRate>10</maxUpdateRate>
+ </rendering:ogre>
+
+
+ <model:physical name="gplane">
+ <xyz>0 0 0</xyz>
+ <rpy>0 0 0</rpy>
+ <static>true</static>
+
+ <body:plane name="plane">
+ <geom:plane name="plane">
+ <kp>1000000.0</kp>
+ <kd>1.0</kd>
+ <normal>0 0 1</normal>
+ <size>51.3 51.3</size>
+ <!-- map3.png -->
+ <material>PR2/floor_texture</material>
+ </geom:plane>
+ </body:plane>
+ </model:physical>
+
+ <!--
+ <model:empty name="ros_model">
+ <body:empty name="ros_body">
+ <controller:ros_node name="ros_node" plugin="libRos_Node.so">
+ <nodeName>simulator_ros_node</nodeName>
+ </controller:ros_node>
+ </body:empty>
+ </model:empty>
+ -->
+
+ <!-- The "desk"-->
+ <!-- small desks -->
+ <model:physical name="desk1_model">
+ <xyz>2.28 -0.21 0</xyz>
+ <rpy>0.0 0.0 0.0 </rpy>
+ <include embedded="true">
+ <!--xi:include href="desk6.model" /--> <!-- block legs -->
+ <xi:include href="desk4.model" /> <!-- skinny pole legs -->
+ </include>
+ </model:physical>
+
+ <!-- The second "desk"-->
+ <model:physical name="desk2_model">
+ <xyz>2.25 -3.0 0</xyz>
+ <rpy>0.0 0.0 0.0 </rpy>
+ <include embedded="true">
+ <xi:include href="desk5.model" />
+ </include>
+ </model:physical>
+
+ <!-- The small cylinder "cup" -->
+ <model:physical name="cylinder1_model">
+ <xyz> 2.5 0.0 1.5</xyz>
+ <rpy> 0.0 0.0 0.0</rpy>
+ <body:cylinder name="cylinder1_body">
+ <geom:cylinder name="cylinder1_geom">
+ <kp>100000000.0</kp>
+ <kd>0.1</kd>
+ <mesh>default</mesh>
+ <size>0.025 0.075</size>
+ <mass> 0.05</mass>
+ <visual>
+ <size> 0.05 0.05 0.075</size>
+ <material>Gazebo/PioneerBody</material>
+ <mesh>unit_cylinder</mesh>
+ </visual>
+ </geom:cylinder>
+ <geom:box name="cylinder1_base_geom">
+ <kp>100000000.0</kp>
+ <kd>0.1</kd>
+ <mesh>default</mesh>
+ <xyz>0.0 0.0 -0.033</xyz>
+ <size>0.05 0.05 0.01</size>
+ <mass> 0.01</mass>
+ <visual>
+ <size> 0.05 0.05 0.01</size>
+ <material>Gazebo/Fish</material>
+ <mesh>unit_box</mesh>
+ </visual>
+ </geom:box>
+ </body:cylinder>
+ </model:physical>
+
+ <!-- The small box "cup" -->
+ <model:physical name="object1_model">
+ <xyz> 0.835 -0.55 0.95</xyz>
+ <rpy> 0.0 0.0 30.0</rpy>
+ <body:box name="object1_body">
+ <geom:box name="object1_geom">
+ <kp>100000000.0</kp>
+ <kd>0.1</kd>
+ <mesh>default</mesh>
+ <size>0.1 0.03 0.03</size>
+ <mass> 0.05</mass>
+ <visual>
+ <size> 0.1 0.030 0.03</size>
+ <material>Gazebo/PioneerBody</material>
+ <mesh>unit_box</mesh>
+ </visual>
+ </geom:box>
+ </body:box>
+
+ <controller:P3D name="p3d_object_controller" plugin="libP3D.so">
+ <updateRate>100.0</updateRate>
+ <bodyName>object1_body</bodyName>
+ <topicName>object1_body_ground_truth</topicName>
+ <frameName>object1_body_ground_truth_frame</frameName>
+ <interface:position name="p3d_object_position"/>
+ </controller:P3D>
+
+ </model:physical>
+
+
+ <!-- The small ball -->
+ <model:physical name="sphere1_model">
+ <xyz> 2.5 -2.8 1.5</xyz>
+ <rpy> 0.0 0.0 0.0</rpy>
+ <body:sphere name="sphere1_body">
+ <geom:sphere name="sphere1_geom">
+ <kp>1000000.0</kp>
+ <kd>1.0</kd>
+ <mesh>default</mesh>
+ <size> 0.15</size>
+ <mass> 1.0</mass>
+ <visual>
+ <size> 0.3 0.3 0.3</size>
+ <material>Gazebo/PioneerBody</material>
+ <mesh>unit_sphere</mesh>
+ </visual>
+ </geom:sphere>
+ </body:sphere>
+ </model:physical>
+
+ <!-- The large ball map3.png -->
+ <model:physical name="sphere2_model">
+ <xyz> 5.85 4.35 1.55</xyz>
+ <rpy> 0.0 0.0 0.0</rpy>
+ <body:sphere name="sphere2_body">
+ <geom:sphere name="sphere2_geom">
+ <kp>1000000.0</kp>
+ <kd>1.0</kd>
+ <mesh>default</mesh>
+ <size> 1.0</size>
+ <mass> 1.0</mass>
+ <visual>
+ <size> 2.0 2.0 2.0</size>
+ <material>Gazebo/Rocky</material>
+ <mesh>unit_sphere</mesh>
+ </visual>
+ </geom:sphere>
+ </body:sphere>
+ </model:physical>
+
+ <!-- The wall in front map3.png -->
+ <model:physical name="wall_2_model">
+ <xyz> 11.6 -1.55 1.0</xyz>
+ <rpy> 0.0 0.0 0.0</rpy>
+ <static>true</static>
+ <body:box name="wall_2_body">
+ <geom:box name="wall_2_geom">
+ <mesh>default</mesh>
+ <size>2.1 32.8 2.0</size>
+ <visual>
+ <size>2.1 32.8 2.0</size>
+ <material>Gazebo/PioneerBody</material>
+ <mesh>unit_box</mesh>
+ </visual>
+ </geom:box>
+ </body:box>
+ </model:physical>
+
+ <!-- The wall behind -->
+ <model:physical name="wall_1_model">
+ <xyz> -11.3 -1.45 1.0</xyz>
+ <rpy> 0.0 0.0 0.0</rpy>
+ <static>true</static>
+ <body:box name="wall_1_body">
+ <geom:box name="wall_1_geom">
+ <mesh>default</mesh>
+ <size>0.4 24.0 2.0</size>
+ <visual>
+ <size>0.4 24.0 2.0</size>
+ <material>Gazebo/PioneerBody</material>
+ <mesh>unit_box</mesh>
+ </visual>
+ </geom:box>
+ </body:box>
+ </model:physical>
+
+ <!-- The wall 3 -->
+ <model:physical name="wall_3_model">
+ <xyz> 6.7 8.05 1.0</xyz>
+ <rpy> 0.0 0.0 0.0</rpy>
+ <static>true</static>
+ <body:box name="wall_3_body">
+ <geom:box name="wall_3_geom">
+ <mesh>default</mesh>
+ <size>7.5 1.2 2.0</size>
+ <visual>
+ <size>7.5 1.2 2.0</size>
+ <material>Gazebo/Chrome</material>
+ <mesh>unit_box</mesh>
+ </visual>
+ </geom:box>
+ </body:box>
+ </model:physical>
+
+
+
+ <model:physical name="robot_model1">
+
+ <controller:ros_time name="ros_time" plugin="libRos_Time.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
+ </controller:ros_time>
+
+ <xyz>0.0 0.0 0.0408</xyz> <!-- bottom of base off the ground by this much, basically wheel height below skirt -->
+ <rpy>0.0 0.0 0.0 </rpy>
+
+ <!-- base, torso and arms -->
+ <include embedded="true">
+ <xi:include href="pr2.model" />
+ </include>
+
+ </model:physical>
+
+
+ <!-- White Directional light -->
+ <!--
+ <model:renderable name="directional_white">
+ <light>
+ <type>directional</type>
+ <direction>0 -0.5 -0.5</direction>
+ <diffuseColor>0.4 0.4 0.4</diffuseColor>
+ <specularColor>0.0 0.0 0.0</specularColor>
+ <attenuation>1 0.0 1.0 0.4</attenuation>
+ </light>
+ </model:renderable>
+ -->
+
+
+</gazebo:world>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|