detect_outlet_test.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2009, 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 import roslib
00035 roslib.load_manifest('pr2_plugs_executive')
00036 
00037 import rospy
00038 
00039 import os
00040 import sys
00041 import time
00042 import tf
00043 
00044 import actionlib;
00045 from pr2_common_action_msgs.msg import *
00046 from pr2_plugs_msgs.msg import *
00047 from pr2_controllers_msgs.msg import *
00048 from actionlib_msgs.msg import *
00049 from trajectory_msgs.msg import JointTrajectoryPoint
00050 from pr2_plugs_actions.posestampedmath import PoseStampedMath
00051 from math import pi
00052 
00053 
00054 # Declare list of actions for easy construction
00055 actions = [('vision_outlet_detection',VisionOutletDetectionAction),]
00056 
00057 def main():
00058   rospy.init_node("plugs_executive")
00059 
00060   # construct tf listener
00061   transformer = tf.TransformListener(True, rospy.Duration(60.0))  
00062   preempt_timeout = rospy.Duration(5.0)
00063 
00064   # Construct action ac
00065   rospy.loginfo("Starting actions.")
00066   ac = dict()
00067   for (name,action) in actions:
00068     ac[name] = actionlib.SimpleActionClient(name,action)
00069 
00070   # Wait for all the ac to start
00071   for (name,action) in actions:
00072     print "Wait for server "+name
00073     ac[name].wait_for_server()
00074 
00075 
00076   detect_outlet_goal = VisionOutletDetectionGoal()
00077 
00078   rospy.loginfo("All actions started.")
00079   rospy.loginfo("Detecting outlet...")
00080   detect_outlet_goal.camera_name = "/forearm_camera_r"
00081   pose_base_outlet = PoseStampedMath()
00082   pose_base_outlet.fromEuler(-0.14, -0.82, 0.29, 0, 0, -pi/2)
00083   detect_outlet_goal.prior = pose_base_outlet.msg
00084   detect_outlet_goal.prior.header.stamp = rospy.Time.now()
00085   detect_outlet_goal.prior.header.frame_id = "base_link"
00086   #detect_outlet_goal.wall_normal = [0, 0, 0]
00087   if ac['vision_outlet_detection'].send_goal_and_wait(detect_outlet_goal, rospy.Duration(30.0), preempt_timeout) != GoalStatus.SUCCEEDED:
00088     rospy.logerr('Vision outlet detection failed')
00089     return
00090 
00091 
00092   outlet_pose = ac['vision_outlet_detection'].get_result().outlet_pose
00093 
00094 
00095   print "GOOD", outlet_pose
00096 
00097   return
00098 
00099 
00100 
00101 if __name__ == "__main__":
00102   main()
00103 


pr2_plugs_gazebo_demo
Author(s): John Hsu
autogenerated on Mon Jan 6 2014 12:04:30