|
From: <hsu...@us...> - 2008-11-26 01:54:58
|
Revision: 7321
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7321&view=rev
Author: hsujohnhsu
Date: 2008-11-26 01:50:52 +0000 (Wed, 26 Nov 2008)
Log Message:
-----------
* Clean up gazebo world files, separated robots models from worlds:
* All world-only file moved to gazebo_worlds
* All test worlds moved to gazebo_worlds/test
* Updated tests
* Pendulum test (dual_link.xml) had a P3D bug fix.
* Update slide, scan, cameras, base.
* Increase damping for multi_link example. Fix controller kdl_chain_name for multi_link example.
Modified Paths:
--------------
pkg/trunk/drivers/simulator/gazebo_plugin/test/testcameras.xml
pkg/trunk/drivers/simulator/gazebo_plugin/test/testpendulum.py
pkg/trunk/drivers/simulator/gazebo_plugin/test/testpendulum.xml
pkg/trunk/drivers/simulator/gazebo_plugin/test/testscan.xml
pkg/trunk/drivers/simulator/gazebo_plugin/test/testslide.xml
pkg/trunk/robot_descriptions/wg_robot_description/dual_link_test/dual_link.xml
pkg/trunk/robot_descriptions/wg_robot_description/multi_link_test/controllers_multi_link.xml
pkg/trunk/robot_descriptions/wg_robot_description/multi_link_test/multi_link.xml
Added Paths:
-----------
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/tablegrasp.world
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/testcameras.world
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/testscan.world
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/testslide.world
pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/teststereo.world
Removed Paths:
-------------
pkg/trunk/robot_descriptions/gazebo_robot_description/world/desk1.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/desk2.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/desk3.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/desk4.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/desk5.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/desk6.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_arm_test.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_dual_link.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_floorobj.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_multi_link.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_obstacle.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_pr2d2.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_prototype1.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_simple.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_single_link.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_tablegrasp.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_wg.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/sicklms200.model
pkg/trunk/robot_descriptions/gazebo_robot_description/world/testcameras.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/testscan.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/testslide.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/teststereo.world
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/test/testcameras.xml
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/test/testcameras.xml 2008-11-26 01:43:02 UTC (rev 7320)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/test/testcameras.xml 2008-11-26 01:50:52 UTC (rev 7321)
@@ -1,16 +1,22 @@
<launch>
<master auto="start" />
- <!-- send single_link.xml to param server -->
- <include file="$(find wg_robot_description)/pr2/send_description.launch" />
-
- <node pkg="gazebo" type="gazebo" args="-g -n $(find gazebo_robot_description)/world/testcameras.world" respawn="false" output="screen">
+ <node pkg="gazebo" type="gazebo" args="-n $(find gazebo_robot_description)/gazebo_worlds/test/testcameras.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" />
<env name="MC_RESOURCE_PATH" value="$(find gazebo_robot_description)/world" />
</node>
+ <!-- send single_link.xml to param server -->
+ <include file="$(find wg_robot_description)/pr2/send_description.launch" />
+
+ <!-- push robotdesc/pr2 to factory and spawn robot in gazebo -->
+ <node pkg="gazebo_plugin" type="urdf2factory" args="robotdesc/pr2 -3 0 0" respawn="false" output="screen" /> <!-- load default arm controller -->
+
+ <!-- load controllers -->
+ <include file="$(find pr2_gazebo)/pr2_default_controllers.launch" />
+
<!--<node pkg="gazebo_plugin" type="groundtruthtransform" args="" respawn="true" />-->
<test test-name="gazebo_plugin_testcameras" pkg="gazebo_plugin" type="testcameras.py" />
</launch>
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/test/testpendulum.py
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/test/testpendulum.py 2008-11-26 01:43:02 UTC (rev 7320)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/test/testpendulum.py 2008-11-26 01:50:52 UTC (rev 7321)
@@ -125,36 +125,24 @@
#print "link1 pose ground truth received"
#self.printPendulum(p3d)
tmpx = p3d.pos.position.x
+ tmpy = p3d.pos.position.y
tmpz = p3d.pos.position.z - 2.0
- #print "link1 origin (" + str(tmpx) + " , " + str(tmpz) + ")"
- self.error1_total += math.sqrt(tmpx*tmpx+tmpz*tmpz)
+
+ self.error1_total += math.sqrt(tmpx*tmpx+tmpy*tmpy+tmpz*tmpz)
self.error1_count += 1
- if math.sqrt(tmpx*tmpx+tmpz*tmpz) > self.error1_max:
- self.error1_max = math.sqrt(tmpx*tmpx+tmpz*tmpz)
+ if math.sqrt(tmpx*tmpx+tmpy*tmpy+tmpz*tmpz) > self.error1_max:
+ self.error1_max = math.sqrt(tmpx*tmpx+tmpy*tmpy+tmpz*tmpz)
def p3dInput2(self, p3d):
- #print "link2 pose ground truth received"
- #self.printPendulum(p3d)
- q = Q(p3d.pos.orientation.x , p3d.pos.orientation.y , p3d.pos.orientation.z , p3d.pos.orientation.w)
- q.normalize()
- v = q.getEuler()
+ tmpx = p3d.pos.position.x
+ tmpy = p3d.pos.position.y
+ tmpz = p3d.pos.position.z - 2.0
- #FIXME: something wrong with the pos, need to fix it. abs masks the problem for now.
- #FIXME: something wrong with the pos, need to fix it. abs masks the problem for now.
- #FIXME: something wrong with the pos, need to fix it. abs masks the problem for now.
- #FIXME: something wrong with the pos, need to fix it. abs masks the problem for now.
- tmpx = abs(p3d.pos.position.x) +0.0 - abs(math.cos(v.z)*math.cos(v.y))
- tmpz = abs(p3d.pos.position.z) -2.0 + abs(math.sin(v.y))
- #math.cos(v.x)*math.cos(v.z)-math.cos(v.x)*math.sin(v.y)*math.cos(v.z))
- #print "link2 origin (" + str(tmpx) + " , " + str(tmpz) + ")"
- #print "link2 raw (" + str(p3d.pos.position.x) + " , " + str(p3d.pos.position.z) + ") total: " + str(self.error2_total)
- #print "link2 correc (" + str(math.cos(v.y)) + " , " + str(math.sin(v.y)) + ") angle: " + str(v.x) +","+str(v.y)+","+str(v.z)
-
- self.error2_total += math.sqrt(tmpx*tmpx+tmpz*tmpz)
+ self.error2_total += math.sqrt(tmpx*tmpx+tmpy*tmpy+tmpz*tmpz)
self.error2_count += 1
- if math.sqrt(tmpx*tmpx+tmpz*tmpz) > self.error2_max:
- self.error2_max = math.sqrt(tmpx*tmpx+tmpz*tmpz)
-
+ if math.sqrt(tmpx*tmpx+tmpy*tmpy+tmpz*tmpz) > self.error2_max:
+ self.error2_max = math.sqrt(tmpx*tmpx+tmpy*tmpy+tmpz*tmpz)
+
def test_pendulum(self):
print "LNK\n"
rospy.Subscriber("link1_pose", PoseWithRatesStamped, self.p3dInput1)
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/test/testpendulum.xml
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/test/testpendulum.xml 2008-11-26 01:43:02 UTC (rev 7320)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/test/testpendulum.xml 2008-11-26 01:50:52 UTC (rev 7321)
@@ -1,20 +1,10 @@
<launch>
<group name="wg">
-
<!-- send single_link.xml to param server -->
- <include file="$(find wg_robot_description)/dual_link_test/send_description.launch" />
+ <include file="$(find examples_gazebo)/dual_link.xml" />
- <node pkg="gazebo" type="gazebo" args="-g -n $(find gazebo_robot_description)/world/robot_dual_link.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" />
- <env name="MC_RESOURCE_PATH" value="$(find gazebo_robot_description)/world" />
- </node>
+ <!--<node pkg="gazebo_plugin" type="groundtruthtransform" args="" respawn="true" />-->
+ <test test-name="gazebo_plugin_testpendulum" pkg="gazebo_plugin" type="testpendulum.py" />
</group>
- <!--node pkg="mechanism_control" type="mech.py" args="sp $(find wg_robot_description)/dual_link_test/controllers_dual_link.xml" respawn="false" output="screen" /--> <!-- load default arm controller -->
- <!--node pkg="robot_mechanism_controllers" type="control.py" args="set test_controller 0.5" respawn="false" output="screen" /--> <!-- open gripper .5 radians -->
-
- <!--<node pkg="gazebo_plugin" type="groundtruthtransform" args="" respawn="true" />-->
- <test test-name="gazebo_plugin_testpendulum" pkg="gazebo_plugin" type="testpendulum.py" />
</launch>
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/test/testscan.xml
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/test/testscan.xml 2008-11-26 01:43:02 UTC (rev 7320)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/test/testscan.xml 2008-11-26 01:50:52 UTC (rev 7321)
@@ -1,47 +1,22 @@
<launch>
<master auto="start" />
- <!-- send single_link.xml to param server -->
- <include file="$(find wg_robot_description)/pr2/send_description.launch" />
-
- <node pkg="gazebo" type="gazebo" args="-g -n $(find gazebo_robot_description)/world/testscan.world" respawn="false" output="screen">
+ <node pkg="gazebo" type="gazebo" args="-n $(find gazebo_robot_description)/gazebo_worlds/test/testscan.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" />
<env name="MC_RESOURCE_PATH" value="$(find gazebo_robot_description)/world" />
</node>
- <node pkg="mechanism_control" type="mech.py" args="sp $(find wg_robot_description)/pr2/controllers.xml" respawn="false" output="screen" />
- <node pkg="robot_mechanism_controllers" type="control.py" args="set tilt_laser_controller 46" respawn="false" output="screen" />
+ <!-- send single_link.xml to param server -->
+ <include file="$(find wg_robot_description)/pr2/send_description.launch" />
+
+ <!-- push robotdesc/pr2 to factory and spawn robot in gazebo -->
+ <node pkg="gazebo_plugin" type="urdf2factory" args="robotdesc/pr2" respawn="false" output="screen" /> <!-- load default arm controller -->
+
+ <!-- load controllers -->
+ <include file="$(find pr2_gazebo)/pr2_default_controllers.launch" />
+
<!--<node pkg="gazebo_plugin" type="groundtruthtransform" args="" respawn="true" />-->
<test test-name="gazebo_plugin_testpointclouds1" pkg="gazebo_plugin" type="testscan.py" />
- <!--test test-name="gazebo_plugin_testpointclouds2" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds3" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds4" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds5" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds6" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds7" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds8" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds9" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds10" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds11" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds12" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds13" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds14" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds15" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds16" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds17" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds18" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds19" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds20" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds21" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds22" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds23" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds24" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds25" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds26" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds27" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds28" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds29" pkg="gazebo_plugin" type="testscan.py" />
- <test test-name="gazebo_plugin_testpointclouds30" pkg="gazebo_plugin" type="testscan.py" /-->
</launch>
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/test/testslide.xml
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/test/testslide.xml 2008-11-26 01:43:02 UTC (rev 7320)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/test/testslide.xml 2008-11-26 01:50:52 UTC (rev 7321)
@@ -1,17 +1,22 @@
<launch>
<master auto="start" />
- <!-- send single_link.xml to param server -->
- <include file="$(find wg_robot_description)/pr2/send_description.launch" />
-
- <node pkg="gazebo" type="gazebo" args="-n $(find gazebo_robot_description)/world/testslide.world" respawn="false" output="screen">
+ <node pkg="gazebo" type="gazebo" args="-n $(find gazebo_robot_description)/gazebo_worlds/test/testslide.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" />
<env name="MC_RESOURCE_PATH" value="$(find gazebo_robot_description)/world" />
</node>
- <node pkg="mechanism_control" type="mech.py" args="sp $(find wg_robot_description)/pr2/controllers.xml" respawn="false" output="screen" />
- <node pkg="pr2_mechanism_controllers" type="control_laser.py" args="tilt_laser_controller sine 20 0.872 0.3475" respawn="false" output="screen" />
- <!--<node pkg="gazebo_plugin" type="groundtruthtransform" args="" respawn="true" />-->
+ <!-- send single_link.xml to param server -->
+ <include file="$(find wg_robot_description)/pr2/send_description.launch" />
+
+ <!-- push robotdesc/pr2 to factory and spawn robot in gazebo -->
+ <node pkg="gazebo_plugin" type="urdf2factory" args="robotdesc/pr2 0 8 110 0 0 90" respawn="false" output="screen" /> <!-- load default arm controller -->
+
+ <!-- load controllers -->
+ <include file="$(find pr2_gazebo)/pr2_default_controllers.launch" />
+
+ <!-- test -->
+ <test test-name="gazebo_plugin_testslide" pkg="gazebo_plugin" type="testslide.py" />
</launch>
Copied: pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/tablegrasp.world (from rev 7310, pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_tablegrasp.world)
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/tablegrasp.world (rev 0)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/tablegrasp.world 2008-11-26 01:50:52 UTC (rev 7321)
@@ -0,0 +1,321 @@
+<?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.01</stepTime>
+ <gravity>0 0 -9.8</gravity>
+ <cfm>0.0000000001</cfm>
+ <erp>0.2</erp>
+ </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>
+ </rendering:gui>
+
+
+ <rendering:ogre>
+ <ambient>1.0 1.0 1.0 1.0</ambient>
+ <sky>
+ <material>Gazebo/CloudySky</material>
+ </sky>
+ <gazeboPath>media</gazeboPath>
+ <shadowTechnique>none</shadowTechnique>
+ <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"-->
+ <model:physical name="desk1_model">
+ <xyz> 0.80 -0.21 -0.35</xyz>
+ <rpy> 0.0 0.0 0.00</rpy>
+ <body:box name="desk1_legs_body">
+ <geom:box name="desk1_legs_geom">
+ <kp>10000000000.0</kp>
+ <kd>1.0</kd>
+ <xyz> 0.0 0.0 0.60</xyz>
+ <mesh>default</mesh>
+ <size>0.5 1.0 0.4</size>
+ <mass> 10.0</mass>
+ <visual>
+ <size> 0.5 1.0 0.40</size>
+ <material>Gazebo/Rocky</material>
+ <mesh>unit_box</mesh>
+ </visual>
+ </geom:box>
+ <geom:box name="desk1_top_geom">
+ <kp>100000000.0</kp>
+ <kd>0.1</kd>
+ <xyz> 0.0 0.0 0.88</xyz>
+ <mesh>default</mesh>
+ <size>0.75 1.5 0.05</size>
+ <mass> 10.0</mass>
+ <visual>
+ <size> 0.75 1.5 0.05</size>
+ <material>Gazebo/Rocky</material>
+ <mesh>unit_box</mesh>
+ </visual>
+ </geom:box>
+ </body:box>
+ </model:physical>
+
+ <!-- The second "desk"-->
+ <model:physical name="desk2_model">
+ <xyz> 2.25 -3.0 -0.10</xyz>
+ <rpy> 0.0 0.0 0.00</rpy>
+ <body:box name="desk2_legs_body">
+ <geom:box name="desk2_legs_geom">
+ <kp>1000000.0</kp>
+ <kd>1.0</kd>
+ <xyz> 0.0 0.0 0.50</xyz>
+ <mesh>default</mesh>
+ <size>0.5 1.0 0.75</size>
+ <mass> 10.0</mass>
+ <visual>
+ <size> 0.5 1.0 0.75</size>
+ <material>Gazebo/Rocky</material>
+ <mesh>unit_box</mesh>
+ </visual>
+ </geom:box>
+ <geom:box name="desk2_top_geom">
+ <kp>1000000.0</kp>
+ <kd>1.0</kd>
+ <xyz> 0.0 0.0 0.90</xyz>
+ <mesh>default</mesh>
+ <size>0.75 1.5 0.05</size>
+ <mass> 10.0</mass>
+ <visual>
+ <size> 0.75 1.5 0.05</size>
+ <material>Gazebo/Rocky</material>
+ <mesh>unit_box</mesh>
+ </visual>
+ </geom:box>
+ </body:box>
+ </model:physical>
+
+ <!-- The small box "cup" -->
+ <model:physical name="object1_model">
+ <xyz> 0.620 -0.45 0.65</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.06</size>
+ <mass> 0.05</mass>
+ <mu1> 500.0 </mu1>
+ <mu2> 500.0 </mu2>
+ <visual>
+ <size> 0.1 0.030 0.06</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>map</frameName>
+ <interface:position name="p3d_object_position"/>
+ </controller:P3D>
+
+ </model:physical>
+
+
+
+ <!--
+ <model:physical name="object1_model">
+ <xyz> 1.035 -0.15 0.55</xyz>
+ <rpy> 0.0 0.0 0.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.01 0.01 0.01</size>
+ <mass> 0.05</mass>
+ <visual>
+ <size> 0.01 0.010 0.01</size>
+ <material>Gazebo/PioneerBody</material>
+ <mesh>unit_box</mesh>
+ </visual>
+ </geom:box>
+ </body:box>
+ </model:physical>
+ -->
+
+ <!-- The small ball -->
+ <model:physical name="sphere1_model">
+ <xyz> 2.5 -2.8 1.0</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:empty name="factory_model">
+ <controller:factory name="factory_controller">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <interface:factory name="factory_iface"/>
+ </controller:factory>
+ </model:empty>
+
+ <!-- White Directional light -->
+ <!--
+ <model:renderable name="directional_white">
+ <light>
+ <type>directional</type>
+ <direction>0 0.0 -1.0</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>
+
Copied: pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/testcameras.world (from rev 7310, pkg/trunk/robot_descriptions/gazebo_robot_description/world/testcameras.world)
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/testcameras.world (rev 0)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/testcameras.world 2008-11-26 01:50:52 UTC (rev 7321)
@@ -0,0 +1,200 @@
+<?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>
+
+ <!-- FIXME: pr2 mimic joints Kp setting is unstable at 0.01 -->
+ <!-- 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>
+
+
+ <rendering:gui>
+ <type>fltk</type>
+ <size>1024 800</size>
+ <pos>0 0</pos>
+ <frames>
+ <row height="100%">
+ <camera width="100%">
+ <xyz>-8 0 3</xyz>
+ <rpy>0 25 0</rpy>
+ <saveFrames>false</saveFrames>
+ <startSaveFrames>true</startSaveFrames>
+ <saveFramePath>testguicameraframes</saveFramePath>
+ </camera>
+ </row>
+ </frames>
+ </rendering:gui>
+
+ <!-- camera used to test Ros_Camera plugin -->
+ <model:physical name="test_camera_model">
+ <body:empty name="test_camera_body">
+ <xyz>-1 0 3</xyz>
+ <rpy>0 45 0</rpy>
+ <sensor:camera name="test_camera_sensor">
+ <alwaysOn>true</alwaysOn>
+ <size>1024 800</size>
+ <hfov>60</hfov>
+ <nearClip>0.1</nearClip>
+ <farClip>100</farClip>
+ <updateRate>15.0</updateRate>
+ <saveFrames>false</saveFrames>
+ <saveFramePath>testcameraframes</saveFramePath>
+ <controller:ros_camera name="test_camera_controller" plugin="libRos_Camera.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>15.0</updateRate>
+ <topicName>test_camera/image</topicName>
+ <frameName>test_camera_body</frameName>
+ <interface:camera name="test_camera_iface" />
+ </controller:ros_camera>
+ </sensor:camera>
+ </body:empty>
+ </model:physical>
+
+ <rendering:ogre>
+ <ambient>1.0 1.0 1.0 1.0</ambient>
+ <gazeboPath>media</gazeboPath>
+ <grid>false</grid>
+ <maxUpdateRate>100</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>Gazebo/White</material>
+ </geom:plane>
+ </body:plane>
+ </model:physical>
+
+
+ <!-- The small cuboidal "cup" -->
+ <model:physical name="cylinder1_model">
+ <xyz> 0.78 1.0 0.075</xyz>
+ <rpy> 0.0 0.0 0.0</rpy>
+ <body:box name="cylinder1_body">
+ <geom:box name="cylinder1_geom">
+ <mesh>default</mesh>
+ <size>0.05 0.05 0.15</size>
+ <mass> 0.5</mass>
+ <cfm>0.000001</cfm>
+ <erp>0.8</erp>
+ <visual>
+ <size> 0.05 0.05 0.15</size>
+ <material>Gazebo/PioneerBody</material>
+ <mesh>unit_box</mesh>
+ </visual>
+ </geom:box>
+ </body:box>
+ </model:physical>
+
+ <!-- The small cylindrical "cup" -->
+ <model:physical name="cylinder1_model">
+ <xyz> 0.78 0.0 0.075</xyz>
+ <rpy> 0.0 0.0 0.0</rpy>
+ <body:cylinder name="cylinder1_body">
+ <geom:cylinder name="cylinder1_geom">
+ <mesh>default</mesh>
+ <size>0.05 0.15</size>
+ <mass> 0.5</mass>
+ <cfm>0.000001</cfm>
+ <erp>0.8</erp>
+ <visual>
+ <size> 0.05 0.05 0.15</size>
+ <material>Gazebo/PioneerBody</material>
+ <mesh>unit_cylinder</mesh>
+ </visual>
+ </geom:cylinder>
+ </body:cylinder>
+ </model:physical>
+
+ <!-- The trimesh cup -->
+ <model:physical name="cup1_model">
+ <xyz> 0.78 -1.0 0</xyz>
+ <rpy> 90.0 0.0 90.0</rpy>
+ <body:trimesh name="cup1_body">
+ <geom:trimesh name="cup1_geom">
+ <kp>1000000000.0</kp>
+ <kd>1.3</kd>
+ <scale> 0.1 0.1 0.1</scale>
+ <mesh>cup.mesh</mesh>
+
+ <massMatrix>true</massMatrix>
+ <mass>0.1</mass>
+ <ixx>5.6522326992070</ixx>
+ <ixy>-0.009719934438</ixy>
+ <ixz>1.2939882264230</ixz>
+ <iyy>5.6694731586520</iyy>
+ <iyz>-0.007379583694</iyz>
+ <izz>3.6831963517260</izz>
+ <cx>0.0</cx>
+ <cy>0.0</cy>
+ <cz>0.0</cz>
+
+ <visual>
+ <scale> 0.1 0.1 0.1</scale>
+ <material>Gazebo/PioneerBody</material>
+ <mesh>cup.mesh</mesh>
+ </visual>
+ </geom:trimesh>
+ </body:trimesh>
+ </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>
+
+ <model:empty name="factory_model">
+ <controller:factory name="factory_controller">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <interface:factory name="factory_iface"/>
+ </controller:factory>
+ </model:empty>
+
+</gazebo:world>
Copied: pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/testscan.world (from rev 7310, pkg/trunk/robot_descriptions/gazebo_robot_description/world/testscan.world)
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/testscan.world (rev 0)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/testscan.world 2008-11-26 01:50:52 UTC (rev 7321)
@@ -0,0 +1,198 @@
+<?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>
+
+ <rendering:gui>
+ <type>fltk</type>
+ <size>1024 800</size>
+ <pos>0 0</pos>
+ <frames>
+ <row height="100%">
+ <camera width="100%">
+ <xyz>-2 0 3</xyz>
+ <rpy>0 45 0</rpy>
+ <saveFrames>false</saveFrames>
+ <startSaveFrames>false</startSaveFrames>
+ <saveFramePath>testpointcloudframes</saveFramePath>
+ </camera>
+ </row>
+ </frames>
+ </rendering:gui>
+
+
+ <rendering:ogre>
+ <ambient>1.0 1.0 1.0 1.0</ambient>
+ <gazeboPath>media</gazeboPath>
+ <grid>false</grid>
+ <maxUpdateRate>100</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>Gazebo/White</material>
+ </geom:plane>
+ </body:plane>
+ </model:physical>
+
+
+ <!-- The small cuboidal "test sphere" -->
+ <model:physical name="sphere1_model">
+ <xyz> 2.5 -0.5 0.1464</xyz>
+ <rpy> 0.0 0.0 0.0 </rpy>
+ <static>false</static>
+ <body:sphere name="sphere1_body">
+ <geom:sphere name="sphere1_geom">
+ <mesh>default</mesh>
+ <size>0.15</size>
+ <mass> 0.5</mass>
+ <cfm>0.000001</cfm>
+ <erp>0.8</erp>
+ <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 small cuboidal "test box" -->
+ <model:physical name="box1_model">
+ <xyz> 2.0 -1.0 0.24</xyz>
+ <rpy> 0.0 0.0 0.0</rpy>
+ <static>false</static>
+ <body:box name="box1_body">
+ <geom:box name="box1_geom">
+ <mesh>default</mesh>
+ <size>0.05 0.30 0.5</size>
+ <mass> 0.5</mass>
+ <cfm>0.000001</cfm>
+ <erp>0.8</erp>
+ <visual>
+ <size> 0.05 0.30 0.5</size>
+ <material>Gazebo/PioneerBody</material>
+ <mesh>unit_box</mesh>
+ </visual>
+ </geom:box>
+ </body:box>
+ </model:physical>
+
+ <!-- The small cylindrical "test cylinder" -->
+ <model:physical name="cylinder1_model">
+ <xyz> 2.0 0.8 1.0</xyz>
+ <rpy> 0.0 0.0 0.0</rpy>
+ <static>false</static>
+ <body:cylinder name="cylinder1_body">
+ <geom:cylinder name="cylinder1_geom">
+ <mesh>default</mesh>
+ <size>0.30 2.0</size>
+ <mass> 0.5</mass>
+ <cfm>0.000001</cfm>
+ <erp>0.8</erp>
+ <visual>
+ <scale> 0.60 0.60 2.0</scale>
+ <material>Gazebo/PioneerBody</material>
+ <mesh>unit_cylinder</mesh>
+ </visual>
+ </geom:cylinder>
+ </body:cylinder>
+ </model:physical>
+
+ <!-- The trimesh cup -->
+ <model:physical name="cup1_model">
+ <xyz> 3.0 0.0 0.009</xyz>
+ <rpy> 90.0 0.0 90.0</rpy>
+ <static>false</static>
+ <body:trimesh name="cup1_body">
+ <geom:trimesh name="cup1_geom">
+ <kp>1000000000.0</kp>
+ <kd>1.3</kd>
+ <scale> 0.3 0.3 0.3</scale>
+ <mesh>cup.mesh</mesh>
+
+ <massMatrix>true</massMatrix>
+ <mass>0.1</mass>
+ <ixx>5.6522326992070</ixx>
+ <ixy>-0.009719934438</ixy>
+ <ixz>1.2939882264230</ixz>
+ <iyy>5.6694731586520</iyy>
+ <iyz>-0.007379583694</iyz>
+ <izz>3.6831963517260</izz>
+ <cx>0.0</cx>
+ <cy>0.0</cy>
+ <cz>0.0</cz>
+
+ <visual>
+ <scale> 0.3 0.3 0.3</scale>
+ <material>Gazebo/PioneerBody</material>
+ <mesh>cup.mesh</mesh>
+ </visual>
+ </geom:trimesh>
+ </body:trimesh>
+ </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>
+
+ <model:empty name="factory_model">
+ <controller:factory name="factory_controller">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <interface:factory name="factory_iface"/>
+ </controller:factory>
+ </model:empty>
+
+</gazebo:world>
Copied: pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/testslide.world (from rev 7310, pkg/trunk/robot_descriptions/gazebo_robot_description/world/testslide.world)
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/testslide.world (rev 0)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/testslide.world 2008-11-26 01:50:52 UTC (rev 7321)
@@ -0,0 +1,344 @@
+<?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>100</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>-10.6 15.3 27.4</xyz>
+ <rpy>0 43.5 -50</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>100</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>
+
+
+
+
+ <!-- This sphere is for debugging the target
+ <model:physical name="debug_model">
+ <xyz> -3.0 0.5 2.6</xyz>
+ <rpy> 0.0 0.0 0.0</rpy>
+ <static>true</static>
+ <body:cylinder name="debug_body">
+ <geom:cylinder name="debug_geom">
+ <kp>100000.0</kp>
+ <kd>1.0</kd>
+ <mesh>default</mesh>
+ <size> 0 0 0</size>
+ <mass> 1.0</mass>
+ <visual>
+ <size> 8 8 1</size>
+ <material>Gazebo/Brick</material>
+ <mesh>unit_cylinder</mesh>
+ </visual>
+ </geom:cylinder>
+ </body:cylinder>
+ </model:physical>-->
+
+
+
+ <model:physical name="endbin_model">
+ <xyz> -5.4 0.0 2.6</xyz>
+ <rpy> 90.0 0.0 90.0</rpy>
+ <static>true</static>
+ <body:trimesh name="endbin_body">
+ <static>true</static>
+ <geom:trimesh name="endbin_geom">
+ <static>true</static>
+ <kp>10000000000.0</kp>
+ <kd>1</kd>
+ <mu1>0.0</mu1>
+ <mu2>0.0</mu2>
+ <scale> 4 2 4</scale>
+ <mesh>cup.mesh</mesh>
+
+ <mass>10.0</mass>
+ <massMatrix>true</massMatrix>
+ <ixx>5.6522326992070</ixx>
+ <ixy>-0.009719934438</ixy>
+ <ixz>1.2939882264230</ixz>
+ <iyy>5.6694731586520</iyy>
+ <iyz>-0.007379583694</iyz>
+ <izz>3.6831963517260</izz>
+ <cx>0.0</cx>
+ <cy>0.0</cy>
+ <cz>0.0</cz>
+
+ <visual>
+ <scale> 4 2 4</scale>
+ <material>Gazebo/Rocky</material>
+ <mesh>cup.mesh</mesh>
+ </visual>
+ </geom:trimesh>
+ </body:trimesh>
+ </model:physical>
+
+ <!-- The Slide-->
+ <model:physical name="slide1_model">
+ <xyz> 0.0 0.0 0.00</xyz>
+ <rpy> 0.0 0.0 0.00</rpy>
+ <body:box name="slide1_legs_body">
+ <geom:box name="slide_base_geom">
+ <kp>10000000000000000</kp>
+ <kd>1</kd>
+ <mu1>10000.0</mu1>
+ <mu2>10000.0</mu2>
+ <xyz> 0.0 5.0 13</xyz>
+
+ <rpy> 45.0 0.0 0.00</rpy>
+ <size> 2.0 14.14 1.0</size>
+ <mass> 1000.0</mass>
+ <visual>
+ <size>2.0 14.14 1.0</size>
+ <material>Gazebo/Red</material>
+ <mesh>unit_box</mesh>
+ </visual>
+ </geom:box>
+
+
+ <geom:box name="slide_side1_geom">
+ <kp>100000</kp>
+ <kd>1</kd>
+ <mu1>0.0</mu1>
+ <mu2>0.0</mu2>
+ <xyz> 1.0 5.0 13.7</xyz>
+ <rpy> 135.0 0.0 0.00</rpy>
+ <size> 1.0 1.0 14.14</size>
+ <mass> 1000.0</mass>
+ <visual>
+ <size>0.1 1.0 14.14</size>
+ <material>Gazebo/Rocky</material>
+ <mesh>unit_box</mesh>
+ </visual>
+ </geom:box>
+ <geom:box name="slide_side2_geom">
+ <kp>100000</kp>
+ <kd>1</kd>
+ <mu1>0.0</mu1>
+ <mu2>0.0</mu2>
+ <xyz> -1.0 7.0 15.5</xyz>
+ <rpy> 135.0 0.0 0.00</rpy>
+ <size> 1.0 1.0 10.0</size>
+ <mass> 1000.0</mass>
+ <visual>
+ <size>0.1 1.0 9.0</size>
+ <material>Gazebo/Rocky</material>
+ <mesh>unit_box</mesh>
+ </visual>
+ </geom:box>
+
+
+
+ <geom:sphere name="slide_end_geom">
+ <kp>1000000.0</kp>
+ <kd>1</kd>
+ <mu1>0.0</mu1>
+ <mu2>0.0</mu2>
+ <mesh>default</mesh>
+ <xyz> 1.0 -1.0 9.5</xyz>
+ <size> 2.5</size>
+ <mass> 1.0</mass>
+ <visual>
+ <size> 5.0 5.0 5.0</size>
+ <material>Gazebo/Rocky</material>
+ <mesh>unit_sphere</mesh>
+ </visual>
+ </geom:sphere>
+
+
+
+
+
+
+
+
+
+
+
+
+ <geom:box name="support_1">
+ <kp>10000000.0</kp>
+ <kd>1</kd>
+ <mu1>1000.0</mu1>
+ <mu2>1000.0</mu2>
+ <xyz>1000.0 1000.0 1.00</xyz>
+ <rpy> 0.0 0.0 0.00</rpy>
+ <mesh>default</mesh>
+ <size> 1.0 1.0 2.0</size>
+ <mass> 10.0</mass>
+ <visual>
+ <size>1.0 1.0 2.0</size>
+ <material>Gazebo/Rocky</material>
+ <mesh>unit_box</mesh>
+ </visual>
+ </geom:box>
+ <geom:box name="support_2">
+ <kp>10000000.0</kp>
+ <kd>1</kd>
+ <mu1>1000.0</mu1>
+ <mu2>1000.0</mu2>
+ <xyz>1000.0 -1000.0 1.00</xyz>
+ <rpy> 0.0 0.0 0.00</rpy>
+ <mesh>default</mesh>
+ <size> 1.0 1.0 2.0</size>
+ <mass> 10.0</mass>
+ <visual>
+ <size>1.0 1.0 2.0</size>
+ <material>Gazebo/Rocky</material>
+ <mesh>unit_box</mesh>
+ </visual>
+ </geom:box>
+ <geom:box name="support_3">
+ <kp>10000000.0</kp>
+ <kd>1</kd>
+ <mu1>1000.0</mu1>
+ <mu2>1000.0</mu2>
+ <xyz>-1000.0 -1000.0 1.00</xyz>
+ <rpy> 0.0 0.0 0.00</rpy>
+ <mesh>default</mesh>
+ <size> 1.0 1.0 2.0</size>
+ <mass> 10.0</mass>
+ <visual>
+ <size>1.0 1.0 2.0</size>
+ <material>Gazebo/Rocky</material>
+ <mesh>unit_box</mesh>
+ </visual>
+ </geom:box>
+ <geom:box name="support_4">
+ <kp>10000000.0</kp>
+ <kd>1</kd>
+ <mu1>1000.0</mu1>
+ <mu2>1000.0</mu2>
+ <xyz>-1000.0 1000.0 1.00</xyz>
+ <rpy> 0.0 0.0 0.00</rpy>
+ <mesh>default</mesh>
+ <size> 1.0 1.0 2.0</size>
+ <mass> 10.0</mass>
+ <visual>
+ <size>1.0 1.0 2.0</size>
+ <material>Gazebo/Rocky</material>
+ <mesh>unit_box</mesh>
+ </visual>
+ </geom:box>
+ </body:box>
+ </model:physical>
+
+
+ <!-- The large ball map3.png -->
+ <model:physical name="ball_model">
+ <xyz> 0.0 8.0 300.0</xyz>
+ <rpy> 0.0 0.0 0.0</rpy>
+ <body:sphere name="ball_body">
+ <geom:sphere name="ball_geom">
+ <kp>100000.0</kp>
+ <kd>1.0</kd>
+ <mu1>5.0</mu1>
+ <mu2>5.0</mu2>
+ <mesh>default</mesh>
+ <size> 0.25</size>
+ <mass> 10.0</mass>
+ <visual>
+ <size> 0.5 0.5 0.5</size>
+ <material>Gazebo/Rocky</material>
+ <mesh>unit_sphere</mesh>
+ </visual>
+ </geom:sphere>
+ </body:sphere>
+ </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>
+ -->
+
+ <model:empty name="factory_model">
+ <controller:factory name="factory_controller">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <interface:factory name="factory_iface"/>
+ </controller:factory>
+ </model:empty>
+
+</gazebo:world>
Copied: pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/teststereo.world (from rev 7310, pkg/trunk/robot_descriptions/gazebo_robot_description/world/teststereo.world)
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/teststereo.world (rev 0)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/gazebo_worlds/test/teststereo.world 2008-11-26 01:50:52 UTC (rev 7321)
@@ -0,0 +1,198 @@
+<?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>
+
+ <rendering:gui>
+ <type>fltk</type>
+ <size>1024 800</size>
+ <pos>0 0</pos>
+ <frames>
+ <row height="100%">
+ <camera width="100%">
+ <xyz>-2 0 3</xyz>
+ <rpy>0 45 0</rpy>
+ <saveFrames>false</saveFrames>
+ <startSaveFrames>false</startSaveFrames>
+ <saveFramePath>testpointcloudframes</saveFramePath>
+ </camera>
+ </row>
+ </frames>
+ </rendering:gui>
+
+
+ <rendering:ogre>
+ <ambient>1.0 1.0 1.0 1.0</ambient>
+ <gazeboPath>media</gazeboPath>
+ <grid>false</grid>
+ <maxUpdateRate>100</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>Gazebo/White</material>
+ </geom:plane>
+ </body:plane>
+ </model:physical>
+
+
+ <!-- The small cuboidal "test sphere" -->
+ <model:physical name="sphere1_model">
+ <xyz> 2.5 -0.5 0.95</xyz>
+ <rpy> 0.0 0.0 0.0 </rpy>
+ <static>true</static>
+ <body:sphere name="sphere1_body">
+ <geom:sphere name="sphere1_geom">
+ <mesh>default</mesh>
+ <size>0.15</size>
+ <mass> 0.5</mass>
+ <cfm>0.000001</cfm>
+ <erp>0.8</erp>
+ <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 small cuboidal "test box" -->
+ <model:physical name="box1_model">
+ <xyz> 2.0 -0.5 0.5</xyz>
+ <rpy> 0.0 0.0 0.0</rpy>
+ <static>true</static>
+ <body:box name="box1_body">
+ <geom:box name="box1_geom">
+ <mesh>default</mesh>
+ <size>0.05 0.30 0.5</size>
+ <mass> 0.5</mass>
+ <cfm>0.000001</cfm>
+ <erp>0.8</erp>
+ <visual>
+ <size> 0.05 0.30 0.5</size>
+ <material>Gazebo/PioneerBody</material>
+ <mesh>unit_box</mesh>
+ </visual>
+ </geom:box>
+ </body:box>
+ </model:physical>
+
+ <!-- The small cylindrical "test cylinder" -->
+ <model:physical name="cylinder1_model">
+ <xyz> 2.0 0.8 1.0</xyz>
+ <rpy> 0.0 0.0 0.0</rpy>
+ <static>true</static>
+ <body:cylinder name="cylinder1_body">
+ <geom:cylinder name="cylinder1_geom">
+ <mesh>default</mesh>
+ <size>0.30 2.0</size>
+ <mass> 0.5</mass>
+ <cfm>0.000001</cfm>
+ <erp>0.8</erp>
+ <visual>
+ <scale> 0.60 0.60 2.0</scale>
+ <material>Gazebo/PioneerBody</material>
+ <mesh>unit_cylinder</mesh>
+ </visual>
+ </geom:cylinder>
+ </body:cylinder>
+ </model:physical>
+
+ <!-- The trimesh cup -->
+ <model:physical name="cup1_model">
+ <xyz> 3.0 0.0 0.5</xyz>
+ <rpy> 90.0 0.0 90.0</rpy>
+ <static>true</static>
+ <body:trimesh name="cup1_body">
+ <geom:trimesh name="cup1_geom">
+ <kp>1000000000.0</kp>
+ <kd>1.3</kd>
+ <scale> 0.3 0.3 0.3</scale>
+ <mesh>cup.mesh</mesh>
+
+ <massMatrix>true</massMatrix>
+ <mass>0.1</mass>
+ <ixx>5.6522326992070</ixx>
+ <ixy>-0.009719934438</ixy>
+ <ixz>1.2939882264230</ixz>
+ <iyy>5.6694731586520</iyy>
+ <iyz>-0.007379583694</iyz>
+ <izz>3.6831963517260</izz>
+ <cx>0.0</cx>
+ <cy>0.0</cy>
+ <cz>0.0</cz>
+
+ <visual>
+ <scale> 0.3 0.3 0.3</scale>
+ <material>Gazebo/PioneerBody</material>
+ <mesh>cup.mesh</mesh>
+ </visual>
+ </geom:trimesh>
+ </body:trimesh>
+ </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>
+
+ <model:empty name="factory_model">
+ <controller:factory name="factory_controller">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>1000.0</updateRate>
+ <interface:factory name="factory_iface"/>
+ </controller:factory>
+ </model:empty>
+
+</gazebo:world>
Deleted: pkg/trunk/robot_descriptions/gazebo_robot_description/world/desk1.model
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/desk1.model 2008-11-26 01:43:02 UTC (rev 7320)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/desk1.model 2008-11-26 01:50:52 UTC (rev 7321)
@@ -1,84 +0,0 @@
-<?xml version="1.0" ?>
-<model:physical 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:body="http://playerstage.sourceforge.net/gazebo/xmlschema/#body" xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom" xmlns:joint="http://playerstage.sourceforge.net/gazebo/xmlschema/#joint" xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller" xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface" xmlns:rendering="http://playerstage.sourceforge.net/gazebo/xmlschema/#rendering" xmlns:physics="http://playerstage.sourceforge.net/gazebo/xmlschema/#physics" name="pr2_model">
- <xyz>0 0 0</xyz>
- <rpy>0 0 0</rpy>
- <body:box name="desk1">
- <xyz>0 0 0.3</xyz>
- <rpy>0 0 0</rpy>
- <geom:box name="desk1top_geom">
- <kp>100000000.0</kp>
- <kd>1.0</kd>
- <xyz>0 0 0.6</xyz>
- <rpy>0 0 0</rpy>
- <massMatrix>true</massMatrix>
- <mass>10.0</mass>
- <ixx>1.0</ixx>
- <ixy>0</ixy>
- <ixz>0</ixz>
- <iyy>1.0</iyy>
- <iyz>0</iyz>
- <izz>1.0</izz>
- <cx>0</cx>
- <cy>0</cy>
- <cz>0</cz>
- <size>0.8 2.0 0.10</size>
- <visual>
- <xyz>0 0 0</xyz>
- <rpy>0 0 0</rpy>
- <scale>0.8 2.0 0.10</scale>
- <mesh>unit_box</mesh>
- <material>Gazebo/Green</material>
- </visual>
- </geom:box>
- <geom:box name="desk1leg_geom">
- <kp>100000000.0</kp>
- <kd>1.0</kd>
- <xyz>0 0 .3</xyz>
- <rpy>0...
[truncated message content] |