|
From: <hsu...@us...> - 2009-09-03 21:26:49
|
Revision: 23787
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23787&view=rev
Author: hsujohnhsu
Date: 2009-09-03 21:26:38 +0000 (Thu, 03 Sep 2009)
Log Message:
-----------
fix test due to base friction change (0), for plug in grasping
Modified Paths:
--------------
pkg/trunk/stacks/pr2_simulator/test_pr2_collision_gazebo/test_slide.launch
pkg/trunk/stacks/pr2_simulator/test_pr2_collision_gazebo/test_slide.py
Modified: pkg/trunk/stacks/pr2_simulator/test_pr2_collision_gazebo/test_slide.launch
===================================================================
--- pkg/trunk/stacks/pr2_simulator/test_pr2_collision_gazebo/test_slide.launch 2009-09-03 21:20:20 UTC (rev 23786)
+++ pkg/trunk/stacks/pr2_simulator/test_pr2_collision_gazebo/test_slide.launch 2009-09-03 21:26:38 UTC (rev 23787)
@@ -11,7 +11,7 @@
<include file="$(find pr2_defs)/launch/upload_pr2.launch" />
<!-- push robot_description to factory and spawn robot in gazebo -->
- <node name="urdf2factory" pkg="gazebo_tools" type="urdf2factory" args="robot_description 0 6 18 0 -75 90 pr2_model" respawn="false" output="screen" />
+ <node name="urdf2factory" pkg="gazebo_tools" type="urdf2factory" args="robot_description 0 6 17 0 -75 90 pr2_model" respawn="false" output="screen" />
<!-- test -->
<test test-name="pr2_test_slide" pkg="test_pr2_collision_gazebo" type="test_slide.py" time-limit="120" />
Modified: pkg/trunk/stacks/pr2_simulator/test_pr2_collision_gazebo/test_slide.py
===================================================================
--- pkg/trunk/stacks/pr2_simulator/test_pr2_collision_gazebo/test_slide.py 2009-09-03 21:20:20 UTC (rev 23786)
+++ pkg/trunk/stacks/pr2_simulator/test_pr2_collision_gazebo/test_slide.py 2009-09-03 21:26:38 UTC (rev 23787)
@@ -42,7 +42,7 @@
import unittest, sys, os, math
import time
import rospy, rostest
-from nav_msgs.msg import *
+from nav_msgs.msg import Odometry
TEST_DURATION = 90.0
TARGET_X = -6.0 + 25.65 #contains offset specified in P3D for base, alternatively, use the gripper roll ground truths
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|