door_demo_test_exec_test.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2008, Willow Garage, Inc.
00005 # All rights reserved.
00006 #
00007 # Redistribution and use in source and binary forms, with or without
00008 # modification, are permitted provided that the following conditions
00009 # are met:
00010 #
00011 #  * Redistributions of source code must retain the above copyright
00012 #    notice, this list of conditions and the following disclaimer.
00013 #  * Redistributions in binary form must reproduce the above
00014 #    copyright notice, this list of conditions and the following
00015 #    disclaimer in the documentation and/or other materials provided
00016 #    with the distribution.
00017 #  * Neither the name of the Willow Garage nor the names of its
00018 #    contributors may be used to endorse or promote products derived
00019 #    from this software without specific prior written permission.
00020 #
00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 # POSSIBILITY OF SUCH DAMAGE.
00033 #
00034 
00035 ## Gazebo collision validation 
00036 PKG = 'pr2_doors_gazebo_demo'
00037 NAME = 'test_door_no_executive'
00038 
00039 import roslib
00040 roslib.load_manifest(PKG)
00041 
00042 import unittest, sys, os, math
00043 import time
00044 import rospy, rostest
00045 from nav_msgs.msg import *
00046 from std_msgs.msg import String
00047 from move_base_msgs.msg import MoveBaseAction, MoveBaseGoal
00048 from door_msgs.msg import Door, DoorAction, DoorGoal
00049 from actionlib import *
00050 
00051 TEST_DURATION = 60000.0
00052 
00053 
00054 class TestDoorNoExecutive(unittest.TestCase):
00055     def __init__(self, *args):
00056         super(TestDoorNoExecutive, self).__init__(*args)
00057 
00058         # initial door
00059         prior_door = Door()
00060         prior_door.frame_p1.x = 1.0
00061         prior_door.frame_p1.y = -0.5
00062         prior_door.frame_p2.x = 1.0
00063         prior_door.frame_p2.y = 0.5
00064         prior_door.door_p1.x = 1.0
00065         prior_door.door_p1.y = -0.5
00066         prior_door.door_p2.x = 1.0
00067         prior_door.door_p2.y = 0.5
00068         prior_door.travel_dir.x = 1.0
00069         prior_door.travel_dir.y = 0.0
00070         prior_door.travel_dir.z = 0.0
00071         prior_door.rot_dir = Door.ROT_DIR_COUNTERCLOCKWISE
00072         prior_door.hinge = Door.HINGE_P2
00073         prior_door.header.frame_id = "base_footprint"
00074         self.door = DoorGoal()
00075         self.door.door = prior_door
00076 
00077         self.move = MoveBaseGoal()
00078         self.move.target_pose.header.frame_id = 'odom_combined'
00079         self.move.target_pose.pose.position.x = 10
00080         self.move.target_pose.pose.position.y = 10
00081         self.move.target_pose.pose.orientation.w = 1
00082         
00083         self.ac_door = SimpleActionClient('move_through_door', DoorAction)
00084         print 'Waiting for open door action server'
00085         self.ac_door.wait_for_server()
00086 
00087         self.ac_move = SimpleActionClient('move_base_local', MoveBaseAction)
00088         print 'Waiting for move base action server'
00089         self.ac_move.wait_for_server()
00090 
00091         rospy.Subscriber("/test_output", String, self.stringOutput)
00092 
00093 
00094     def stringOutput(self, str):
00095         print str.data
00096         
00097     
00098     def test_door_no_executive(self):
00099        self.assert_(self.ac_door.send_goal_and_wait(self.door, rospy.Duration(TEST_DURATION), rospy.Duration(5.0)))
00100        self.assert_(self.ac_move.send_goal_and_wait(self.move, rospy.Duration(TEST_DURATION), rospy.Duration(5.0)))
00101     
00102 
00103 
00104 if __name__ == '__main__':
00105     rospy.init_node('open_door_test', anonymous=True)
00106     rostest.run(PKG, sys.argv[0], TestDoorNoExecutive, sys.argv) #, text_mode=True)
00107 


pr2_doors_gazebo_demo
Author(s): John Hsu
autogenerated on Mon Jan 6 2014 12:13:02