|
From: <hsu...@us...> - 2008-09-25 22:23:33
|
Revision: 4686
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=4686&view=rev
Author: hsujohnhsu
Date: 2008-09-25 22:23:20 +0000 (Thu, 25 Sep 2008)
Log Message:
-----------
* update robot height on startup so it does not bounce around.
* laser scan test for base scan working and passes.
* move hztest to gazebo_plugin
Modified Paths:
--------------
pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Block_Laser.cc
pkg/trunk/drivers/simulator/gazebo_plugin/test/testscan.py
pkg/trunk/drivers/simulator/gazebo_plugin/test/testscan.xml
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_arm_test.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_arm_test_headless.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_floorobj.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_headless.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_obs.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_obstacle.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_test_coord.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_wg.world
pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_wg_headless.world
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
Added Paths:
-----------
pkg/trunk/drivers/simulator/gazebo_plugin/test/hztest.xml
pkg/trunk/drivers/simulator/gazebo_plugin/test/odom_hztest.xml
pkg/trunk/drivers/simulator/gazebo_plugin/test/rostime_hztest.xml
pkg/trunk/robot_descriptions/gazebo_robot_description/world/teststereo.world
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Block_Laser.cc
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Block_Laser.cc 2008-09-25 21:34:42 UTC (rev 4685)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/Ros_Block_Laser.cc 2008-09-25 22:23:20 UTC (rev 4686)
@@ -188,7 +188,6 @@
double r1, r2, r3, r4, r; // four corner values + interpolated range
int v;
-
Angle maxAngle = this->myParent->GetMaxAngle();
Angle minAngle = this->myParent->GetMinAngle();
@@ -284,6 +283,12 @@
v = (int) this->myParent->GetRetro(j1) || (int) this->myParent->GetRetro(j2) ||
(int) this->myParent->GetRetro(j3) || (int) this->myParent->GetRetro(j4);
+ std::cout << " block debug "
+ << " ij("<<i<<","<<j<<")"
+ << " j1234("<<j1<<","<<j2<<","<<j3<<","<<j4<<")"
+ << " r1234("<<r1<<","<<r2<<","<<r3<<","<<r4<<")"
+ << std::endl;
+
this->laserIface->data->ranges[i] = r + minRange;
this->laserIface->data->intensity[i] = v;
Copied: pkg/trunk/drivers/simulator/gazebo_plugin/test/hztest.xml (from rev 4680, pkg/trunk/demos/2dnav-gazebo/hztest.xml)
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/test/hztest.xml (rev 0)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/test/hztest.xml 2008-09-25 22:23:20 UTC (rev 4686)
@@ -0,0 +1,36 @@
+<launch>
+ <!-- Bring up the node we want to test. -->
+ <include file="$(find gazebo_robot_description)/pr2_gazebo_actuators.xml"/>
+
+ <!-- Run hztest -->
+ <!-- Test for publication of 'base_scan' topic -->
+ <test test-name="hztest_test_scan" pkg="rostest" type="hztest" name="base_scan_test">
+ <!-- The topic to listen for -->
+ <param name="topic" value="base_scan" />
+ <!-- The expected publication rate [Hz]. Set to 0.0 to only check that
+ at least one message is received. -->
+ <param name="hz" value="5.0" />
+ <!-- Acceptable error in the publication rate [Hz]. Ignored if hz is set
+ to 0.0. -->
+ <param name="hzerror" value="3.0" />
+ <!-- Time to listen for [seconds] -->
+ <param name="test_duration" value="5.0" />
+ <!-- Whether each inter-message time interval should be checked against
+ the expected publication rate and error bound [boolean]. If true, then
+ the test will fail if the time elapsed between *any* two consecutive
+ messages exceeded the specified limits. If false, then we only check
+ the average publication rate over the entire test. Default: false. -->
+ <param name="check_intervals" value="false" />
+ </test>
+
+ <!-- Test for publication of 'tilt_scan' topic. -->
+ <test test-name="hztest_test_tilt_scan" pkg="rostest" type="hztest" name="tilt_scan_test">
+ <!-- Note how we use a different parameter namespace and node name
+ for this test (tilt_scan_test vs. scan_test). -->
+ <param name="topic" value="tilt_scan" />
+ <param name="hz" value="5.0" />
+ <param name="hzerror" value="3.0" />
+ <param name="test_duration" value="5.0" />
+ <param name="check_intervals" value="false" />
+ </test>
+</launch>
Copied: pkg/trunk/drivers/simulator/gazebo_plugin/test/odom_hztest.xml (from rev 4680, pkg/trunk/demos/2dnav-gazebo/odom_hz_test.xml)
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/test/odom_hztest.xml (rev 0)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/test/odom_hztest.xml 2008-09-25 22:23:20 UTC (rev 4686)
@@ -0,0 +1,15 @@
+<launch>
+ <!-- Bring up the node we want to test. -->
+ <include file="$(find gazebo_robot_description)/pr2_gazebo_actuators_headless.xml"/>
+
+ <!-- Test for publication of 'odom' topic. -->
+ <test test-name="hztest_test_odom" pkg="rostest" type="hztest" name="odom_test">
+ <!-- Note how we use a different parameter namespace and node name
+ for this test (odom_test vs. scan_test). -->
+ <param name="topic" value="odom" />
+ <param name="hz" value="25.0" />
+ <param name="hzerror" value="10.0" />
+ <param name="test_duration" value="5.0" />
+ <param name="check_intervals" value="false" />
+ </test>
+</launch>
Copied: pkg/trunk/drivers/simulator/gazebo_plugin/test/rostime_hztest.xml (from rev 4680, pkg/trunk/demos/2dnav-gazebo/rostime_hztest.xml)
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/test/rostime_hztest.xml (rev 0)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/test/rostime_hztest.xml 2008-09-25 22:23:20 UTC (rev 4686)
@@ -0,0 +1,15 @@
+<launch>
+ <!-- Bring up the node we want to test. -->
+ <include file="$(find gazebo_robot_description)/pr2_gazebo_actuators.xml"/>
+
+ <!-- Test for publication of 'odom' topic. -->
+ <test test-name="hztest_test_rostime" pkg="rostest" type="hztest" name="rostime_test">
+ <!-- Note how we use a different parameter namespace and node name
+ for this test (odom_test vs. scan_test). -->
+ <param name="topic" value="ros_time" />
+ <param name="hz" value="25.0" />
+ <param name="hzerror" value="10.0" />
+ <param name="test_duration" value="10.0" />
+ <param name="check_intervals" value="false" />
+ </test>
+</launch>
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/test/testscan.py
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/test/testscan.py 2008-09-25 21:34:42 UTC (rev 4685)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/test/testscan.py 2008-09-25 22:23:20 UTC (rev 4686)
@@ -37,113 +37,121 @@
PKG = 'gazebo_plugin'
NAME = 'testscan'
+import math
import rostools
rostools.update_path(PKG)
+rostools.update_path('rostest')
+rostools.update_path('std_msgs')
+rostools.update_path('robot_msgs')
+rostools.update_path('rostest')
+rostools.update_path('rospy')
+
import sys, unittest
import os, os.path, threading, time
import rospy, rostest
from std_msgs.msg import *
-TARGET_RANGES = [10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 1.02020120621, 1.02020120621, 0.994996726513, 0.978999376297, 0.966377794743, 0.954521596432,
- 0.946537315845, 0.938699901104, 0.931005299091, 0.923867344856, 0.918545365334, 0.913301467896, 0.908134281635,
- 0.903042435646, 0.898042142391, 0.894432485104, 0.890870153904, 0.887354433537, 0.883884489536, 0.880459964275,
- 0.877079963684, 0.874371290207, 0.87203514576, 0.869730234146, 0.867456197739, 0.865212798119, 0.862999677658,
- 0.860816538334, 0.858880698681, 0.857526659966, 0.856195926666, 0.854888141155, 0.853603363037, 0.852341353893,
- 0.851101875305, 0.849884927273, 0.848810076714, 0.848314881325, 0.847839236259, 0.847383201122, 0.846946537495,
- 0.846529304981, 0.846131563187, 0.845753133297, 0.845394074917, 0.845493674278, 0.845822274685, 0.846170067787,
- 0.846537172794, 0.846923649311, 0.847329437733, 0.847754657269, 0.848199427128, 0.848777770996, 0.849939465523,
- 0.851123332977, 0.852329492569, 0.853558063507, 0.854809224606, 0.856083095074, 0.85737991333, 0.858728706837,
- 0.860843420029, 0.862987458706, 0.865161120892, 0.867364525795, 0.869598209858, 0.871862351894, 0.874157428741,
- 0.877089142799, 0.880418121815, 0.883790969849, 0.887208282948, 0.890670895576, 0.894179165363, 0.898019433022,
- 0.902963221073, 0.907979309559, 0.913068950176, 0.918233573437, 0.92347484827, 0.930853664875, 0.938418328762,
- 0.946122050285, 0.953988730907, 0.966012120247, 0.978349208832, 0.994455933571, 0.70413172245, 0.70413172245,
- 0.699802815914, 0.69553899765, 0.691339015961, 0.687201619148, 0.683125734329, 0.679109990597, 0.681101262569,
- 0.683556973934, 0.686044812202, 0.688565373421, 0.691119015217, 0.693706274033, 0.696327507496, 0.698884189129,
- 0.702267229557, 0.706037044525, 0.709827125072, 0.71367174387, 0.717571854591, 0.721528351307, 0.725542485714,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 1.84625160694, 1.84625160694,
- 1.84267711639, 1.83915615082, 1.83568811417, 1.83227264881, 1.82890927792, 1.82559776306, 1.82233738899,
- 1.8191280365, 1.81596922874, 1.81286048889, 1.80980145931, 1.80679190159, 1.80383121967, 1.80091929436,
- 1.79805552959, 1.79523980618, 1.79247164726, 1.78975069523, 1.78707683086, 1.78444945812, 1.78186845779,
- 1.77933347225, 1.77684426308, 1.77440047264, 1.77200174332, 1.76964783669, 1.76733863354, 1.76507377625,
- 1.76285290718, 1.76067578793, 1.75854229927, 1.75645208359, 1.75440490246, 1.75240063667, 1.7504389286,
- 1.74851965904, 1.74664247036, 1.74480736256, 1.743013978, 1.74126207829, 1.73955154419, 1.73788225651,
- 1.73625385761, 1.73466622829, 1.73311936855, 1.73161280155, 1.7301466465, 1.72872054577, 1.72733438015,
- 1.72598814964, 1.72468149662, 1.72341430187, 1.7221865654, 1.72099816799, 1.71984875202, 1.7187384367,
- 1.7176669836, 1.71663427353, 1.71564018726, 1.7146846056, 1.71376752853, 1.71288883686, 1.71204829216,
- 1.71124601364, 1.71048164368, 1.70975542068, 1.70906698704, 1.70841646194, 1.7078037262, 1.70722866058,
- 1.7066911459, 1.70619130135, 1.70572900772, 1.70530414581, 1.70491671562, 1.70456671715, 1.70425403118,
- 1.70397877693, 1.70374071598, 1.70353996754, 1.70337641239, 1.70325005054, 1.70316100121, 1.70310914516,
- 1.70309448242, 1.70311701298, 1.70317673683, 1.70327365398, 1.70340788364, 1.70357918739, 1.70378780365,
- 1.70403373241, 1.70431697369, 1.70463752747, 1.70499539375, 1.70539069176, 1.70582354069, 1.70629370213,
- 1.7068015337, 1.7073469162, 1.70792996883, 1.7085506916, 1.70920920372, 1.70990550518, 1.7106398344,
- 1.71141219139, 1.71222257614, 1.71307110786, 1.71395790577, 1.71488320827, 1.71584677696, 1.71684896946,
- 1.71788990498, 1.71896958351, 1.72008812428, 1.72124576569, 1.72244250774, 1.72367858887, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 1.05949211121,
- 1.05949211121, 1.05673527718, 1.05401551723, 1.05133235455, 1.04868555069, 1.04607462883, 1.04349911213,
- 1.04095888138, 1.03845345974, 1.03993999958, 1.05028426647, 1.06085050106, 1.07164573669, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0,
- 10.0, 10.0, 10.0, 10.0]
+TARGET_RANGES = [
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 2.05170464516, 2.04536008835, 2.03909778595, 2.03291654587, 2.02681565285,
+2.02079415321, 2.01485085487, 2.00898480415, 2.0031952858, 1.99748134613, 1.99184203148, 1.98627638817,
+1.98078382015, 1.97536325455, 1.9700139761, 1.96473526955, 1.95952606201, 1.95438587666, 1.94931387901,
+1.94430923462, 1.93937122822, 1.93449926376, 1.92969250679, 1.92495036125, 1.92027211189, 1.91565704346,
+1.91110467911, 1.90661418438, 1.90218496323, 1.91215276718, 1.93008923531, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 2.64686512947, 2.6173157692, 2.59563803673, 2.57963132858, 2.5657658577,
+2.55445694923, 2.54415798187, 2.53618431091, 2.52831435204, 2.5224199295, 2.51713490486, 2.51194572449,
+2.50885725021, 2.50583004951, 2.50296163559, 2.50192046165, 2.50093340874, 2.5, 2.50093340874,
+2.50192022324, 2.50296139717, 2.50582957268, 2.50885748863, 2.51194500923, 2.51713514328, 2.52241945267,
+2.52831435204, 2.53618454933, 2.54415798187, 2.55445718765, 2.5657658577, 2.57963109016, 2.59563827515,
+2.6173157692, 2.64686512947, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 2.74098372459, 2.72118186951, 2.72313261032, 2.72514390945, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 1.85238564014, 1.80339097977, 1.77707922459, 1.75727534294, 1.74103367329,
+1.72714829445, 1.71498286724, 1.70415234566, 1.69440209866, 1.68555378914, 1.67747652531, 1.67007064819,
+1.66325867176, 1.6569788456, 1.65118086338, 1.64582335949, 1.64087188244, 1.63629746437, 1.63207530975,
+1.62818443775, 1.62460672855, 1.62132656574, 1.61833024025, 1.61560595036, 1.61314368248, 1.61093437672,
+1.60897052288, 1.60724556446, 1.6057536602, 1.60449028015, 1.60345125198, 1.60263371468, 1.60203504562,
+1.60165333748, 1.60148763657, 1.60153746605, 1.60180282593, 1.60228455067, 1.60298418999, 1.60390377045,
+1.60504591465, 1.60641443729, 1.60801339149, 1.60984802246, 1.61192440987, 1.61424958706, 1.61683177948,
+1.61968040466, 1.62280631065, 1.62622225285, 1.62994265556, 1.6339840889, 1.63836622238, 1.64311158657,
+1.64824676514, 1.65380322933, 1.65981829166, 1.66633713245, 1.6734149456, 1.68112039566, 1.68954002857,
+1.69878637791, 1.709010005, 1.72041964531, 1.73332083225, 1.74819290638, 1.76587283611, 1.7881039381,
+1.82019233704, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907,
+10.0500001907, 10.0500001907, 10.0500001907, 10.0500001907, ]
@@ -166,25 +174,22 @@
def pointInput(self, cloud):
i = 0
- print "Input"
+ print "Input laser scan received"
self.printPointCloud(cloud)
while (i < len(cloud.ranges) and i < len(TARGET_RANGES)):
d = cloud.ranges[i] - TARGET_RANGES[i]
if ((d < -0.001) or (d > 0.001)):
return
i = i + 1
-
- os.system("killall gazebo")
self.success = True
def test_pointcloud(self):
print "LNK\n"
rospy.TopicSub("base_scan", LaserScan, self.pointInput)
rospy.ready(NAME, anonymous=True)
- timeout_t = time.time() + 30.0 #30 seconds
+ timeout_t = time.time() + 5.0
while not rospy.is_shutdown() and not self.success and time.time() < timeout_t:
time.sleep(0.1)
- os.system("killall gazebo")
self.assert_(self.success)
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/test/testscan.xml
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/test/testscan.xml 2008-09-25 21:34:42 UTC (rev 4685)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/test/testscan.xml 2008-09-25 22:23:20 UTC (rev 4686)
@@ -7,6 +7,8 @@
<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" />
<!--<node pkg="gazebo_plugin" type="groundtruthtransform" args="" respawn="true" />-->
<test test-name="gazebo_plugin_testpointclouds" pkg="gazebo_plugin" type="testscan.py" />
</launch>
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot.world 2008-09-25 21:34:42 UTC (rev 4685)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot.world 2008-09-25 22:23:20 UTC (rev 4686)
@@ -323,7 +323,7 @@
<interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
</controller:ros_time>
- <xyz>0.0 0.0 0.02</xyz> <!-- bottom of base off the ground by this much, basically wheel height below skirt -->
+ <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 -->
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_arm_test.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_arm_test.world 2008-09-25 21:34:42 UTC (rev 4685)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_arm_test.world 2008-09-25 22:23:20 UTC (rev 4686)
@@ -163,7 +163,7 @@
</controller:ros_time>
<!-- location of robot in the world -->
- <xyz>0.0 0.0 0.0</xyz>
+ <xyz>0.0 0.0 0.0408</xyz>
<rpy>0.0 0.0 0.0</rpy>
<!-- base and arm -->
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_arm_test_headless.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_arm_test_headless.world 2008-09-25 21:34:42 UTC (rev 4685)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_arm_test_headless.world 2008-09-25 22:23:20 UTC (rev 4686)
@@ -163,7 +163,7 @@
</controller:ros_time>
<!-- location of robot in the world -->
- <xyz>0.0 0.0 0.0</xyz>
+ <xyz>0.0 0.0 0.0408</xyz>
<rpy>0.0 0.0 0.0</rpy>
<!-- base and arm -->
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_floorobj.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_floorobj.world 2008-09-25 21:34:42 UTC (rev 4685)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_floorobj.world 2008-09-25 22:23:20 UTC (rev 4686)
@@ -348,7 +348,7 @@
<interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
</controller:ros_time>
- <xyz>0.0 0.0 0.02</xyz> <!-- bottom of base off the ground by this much, basically wheel height below skirt -->
+ <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 -->
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_headless.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_headless.world 2008-09-25 21:34:42 UTC (rev 4685)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_headless.world 2008-09-25 22:23:20 UTC (rev 4686)
@@ -323,7 +323,7 @@
<interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
</controller:ros_time>
- <xyz>0.0 0.0 0.02</xyz> <!-- bottom of base off the ground by this much, basically wheel height below skirt -->
+ <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 -->
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_obs.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_obs.world 2008-09-25 21:34:42 UTC (rev 4685)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_obs.world 2008-09-25 22:23:20 UTC (rev 4686)
@@ -348,7 +348,7 @@
<interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
</controller:ros_time>
- <xyz>0.0 0.0 0.02</xyz> <!-- bottom of base off the ground by this much, basically wheel height below skirt -->
+ <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 -->
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_obstacle.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_obstacle.world 2008-09-25 21:34:42 UTC (rev 4685)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_obstacle.world 2008-09-25 22:23:20 UTC (rev 4686)
@@ -343,7 +343,7 @@
<interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
</controller:ros_time>
- <xyz>0.0 0.0 0.02</xyz> <!-- bottom of base off the ground by this much, basically wheel height below skirt -->
+ <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 -->
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_single_link.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_single_link.world 2008-09-25 21:34:42 UTC (rev 4685)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_single_link.world 2008-09-25 22:23:20 UTC (rev 4686)
@@ -175,7 +175,7 @@
<interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
</controller:ros_time>
- <xyz>0.0 0.0 0.0 </xyz>
+ <xyz>0.0 0.0 0.0408 </xyz>
<rpy>0.0 0.0 0.0 </rpy>
<!-- single link -->
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_tablegrasp.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_tablegrasp.world 2008-09-25 21:34:42 UTC (rev 4685)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_tablegrasp.world 2008-09-25 22:23:20 UTC (rev 4686)
@@ -304,7 +304,7 @@
<interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
</controller:ros_time>
- <xyz>0.0 0.0 0.02</xyz> <!-- bottom of base off the ground by this much, basically wheel height below skirt -->
+ <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 -->
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_test_coord.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_test_coord.world 2008-09-25 21:34:42 UTC (rev 4685)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_test_coord.world 2008-09-25 22:23:20 UTC (rev 4686)
@@ -348,7 +348,7 @@
<interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
</controller:ros_time>
- <xyz>0.0 0.0 0.02</xyz> <!-- bottom of base off the ground by this much, basically wheel height below skirt -->
+ <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 -->
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_wg.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_wg.world 2008-09-25 21:34:42 UTC (rev 4685)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_wg.world 2008-09-25 22:23:20 UTC (rev 4686)
@@ -100,7 +100,7 @@
<interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
</controller:ros_time>
- <xyz>0.0 0.0 0.02</xyz> <!-- bottom of base off the ground by this much, basically wheel height below skirt -->
+ <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 -->
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_wg_headless.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_wg_headless.world 2008-09-25 21:34:42 UTC (rev 4685)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/robot_wg_headless.world 2008-09-25 22:23:20 UTC (rev 4686)
@@ -100,7 +100,7 @@
<interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
</controller:ros_time>
- <xyz>0.0 0.0 0.02</xyz> <!-- bottom of base off the ground by this much, basically wheel height below skirt -->
+ <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 -->
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/testcameras.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/testcameras.world 2008-09-25 21:34:42 UTC (rev 4685)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/testcameras.world 2008-09-25 22:23:20 UTC (rev 4686)
@@ -73,9 +73,6 @@
<rendering:ogre>
<ambient>1.0 1.0 1.0 1.0</ambient>
- <sky>
- <material>Gazebo/White</material>
- </sky>
<gazeboPath>media</gazeboPath>
<grid>false</grid>
<maxUpdateRate>100</maxUpdateRate>
@@ -192,7 +189,7 @@
<interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
</controller:ros_time>
- <xyz> -3.0 0.0 0.0 </xyz>
+ <xyz> -3.0 0.0 0.0408 </xyz>
<rpy> 0.0 0.0 0.0 </rpy>
<!-- base, torso and arms -->
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/testscan.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/testscan.world 2008-09-25 21:34:42 UTC (rev 4685)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/testscan.world 2008-09-25 22:23:20 UTC (rev 4686)
@@ -36,7 +36,7 @@
<frames>
<row height="100%">
<camera width="100%">
- <xyz>-1 0 3</xyz>
+ <xyz>-2 0 3</xyz>
<rpy>0 45 0</rpy>
<saveFrames>false</saveFrames>
<startSaveFrames>false</startSaveFrames>
@@ -49,9 +49,6 @@
<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>
@@ -71,59 +68,47 @@
<normal>0 0 1</normal>
<size>51.3 51.3</size>
<!-- map3.png -->
- <material>PR2/floor_texture</material>
+ <material>Gazebo/White</material>
</geom:plane>
</body:plane>
</model:physical>
- <!-- The "desk"-->
- <model:physical name="desk1_model">
- <xyz> 2.28 -0.21 -0.10</xyz>
- <rpy> 0.0 0.0 0.50</rpy>
- <body:box name="desk1_legs_body">
- <geom:box name="desk1_legs_geom">
- <kp>100000000.0</kp>
- <kd>1.0</kd>
- <xyz> 0.0 0.0 0.50</xyz>
+ <!-- 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.5 1.0 0.75</size>
- <mass> 10.0</mass>
+ <size>0.15</size>
+ <mass> 0.5</mass>
+ <cfm>0.000001</cfm>
+ <erp>0.8</erp>
<visual>
- <size> 0.5 1.0 0.75</size>
- <material>Gazebo/Rocky</material>
- <mesh>unit_box</mesh>
+ <size> 0.3 0.3 0.3</size>
+ <material>Gazebo/PioneerBody</material>
+ <mesh>unit_sphere</mesh>
</visual>
- </geom:box>
- <geom:box name="desk1_top_geom">
- <kp>100000000.0</kp>
- <kd>0.1</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>
+ </geom:sphere>
+ </body:sphere>
</model:physical>
- <!-- The small cuboidal "cup" -->
- <model:physical name="cylinder1_model">
- <xyz> 0.78 1.0 0.25</xyz>
+ <!-- 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>
- <body:box name="cylinder1_body">
- <geom:box name="cylinder1_geom">
+ <static>false</static>
+ <body:box name="box1_body">
+ <geom:box name="box1_geom">
<mesh>default</mesh>
- <size>0.05 0.05 0.5</size>
+ <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.05 0.5</size>
+ <size> 0.05 0.30 0.5</size>
<material>Gazebo/PioneerBody</material>
<mesh>unit_box</mesh>
</visual>
@@ -131,19 +116,20 @@
</body:box>
</model:physical>
- <!-- The small cylindrical "cup" -->
+ <!-- The small cylindrical "test cylinder" -->
<model:physical name="cylinder1_model">
- <xyz> 0.78 0.0 1.0</xyz>
+ <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.05 2.0</size>
+ <size>0.30 2.0</size>
<mass> 0.5</mass>
<cfm>0.000001</cfm>
<erp>0.8</erp>
<visual>
- <scale> 0.05 0.05 2.0</scale>
+ <scale> 0.60 0.60 2.0</scale>
<material>Gazebo/PioneerBody</material>
<mesh>unit_cylinder</mesh>
</visual>
@@ -153,8 +139,9 @@
<!-- The trimesh cup -->
<model:physical name="cup1_model">
- <xyz> 0.78 -1.0 0</xyz>
+ <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>
@@ -202,7 +189,7 @@
<interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
</controller:ros_time>
- <xyz>0.0 0.0 0.0 </xyz>
+ <xyz>0.0 0.0 0.0408 </xyz>
<rpy>0.0 0.0 0.0 </rpy>
<!-- base, torso and arms -->
Modified: pkg/trunk/robot_descriptions/gazebo_robot_description/world/testslide.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/testslide.world 2008-09-25 21:34:42 UTC (rev 4685)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/testslide.world 2008-09-25 22:23:20 UTC (rev 4686)
@@ -334,7 +334,7 @@
<interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
</controller:ros_time>
- <xyz>0.0 8.0 60.25</xyz>
+ <xyz>0.0 8.0 0.0408</xyz>
<rpy>0.0 0.0 90.0 </rpy>
<!-- base, torso and arms -->
Added: pkg/trunk/robot_descriptions/gazebo_robot_description/world/teststereo.world
===================================================================
--- pkg/trunk/robot_descriptions/gazebo_robot_description/world/teststereo.world (rev 0)
+++ pkg/trunk/robot_descriptions/gazebo_robot_description/world/teststereo.world 2008-09-25 22:23:20 UTC (rev 4686)
@@ -0,0 +1,203 @@
+<?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 -->
+ <physics:ode>
+ <stepTime>0.01</stepTime>
+ <gravity>0 0 -9.8</gravity>
+ <cfm>0.0000000001</cfm>
+ <erp>0.2</erp>
+ </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:physical name="robot_model1">
+
+ <controller:ros_time name="ros_time" plugin="libRos_Time.so">
+ <alwaysOn>true</alwaysOn>
+ <updateRate>100.0</updateRate>
+ <interface:audio name="dummy_ros_time_iface_should_not_be_here"/>
+ </controller:ros_time>
+
+ <xyz>0.0 0.0 0.0408 </xyz>
+ <rpy>0.0 0.0 0.0 </rpy>
+
+ <!-- base, torso and arms -->
+ <include embedded="true">
+ <xi:include href="pr2_xml.model" />
+ </include>
+
+ </model:physical>
+
+
+</gazebo:world>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|