$search
00001 #!/usr/bin/env python 00002 # 00003 # head_pointer.py 00004 # Mac Mason <mmason@willowgarage.com> 00005 # 00006 # Make the head point at the currently-published "best plane", or generally 00007 # forward if there isn't one. To keep ourselves from continually looking 00008 # backward, we set a maximum_angle flag, which decides just how far backward 00009 # we're willing to look. (Specifically, it sets how far off of "frontward" 00010 # we're willing to look). 00011 00012 import sys 00013 import math 00014 import roslib; roslib.load_manifest('semanticmodel') 00015 import rospy 00016 import actionlib 00017 from actionlib_msgs.msg import * 00018 from pr2_controllers_msgs.msg import * 00019 from geometry_msgs.msg import * 00020 import tf 00021 import dynamic_reconfigure.client 00022 00023 # Get all started up. 00024 rospy.init_node('head_pointer') 00025 00026 # An extra command-line argument turns us into a very simple algorithm. 00027 ALWAYS_LOOK_FORWARD = False 00028 00029 client = actionlib.SimpleActionClient( 00030 '/head_traj_controller/point_head_action', PointHeadAction) 00031 rospy.loginfo("Waiting for actionlib server...") 00032 client.wait_for_server() 00033 rospy.loginfo("...got actionlib server") 00034 00035 listener = tf.TransformListener() 00036 00037 # How far we're willing to turn the head. 00038 LIMIT = math.radians(60.0) 00039 00040 while not rospy.is_shutdown(): 00041 plane = False 00042 try: 00043 time = listener.getLatestCommonTime('/map', '/best_plane') 00044 rospy.logdebug( 00045 "Delta is {0}.".format((rospy.get_rostime() - time).to_sec())) 00046 plane = True 00047 except tf.Exception as e: 00048 rospy.loginfo("Failed first lookup of tf transform." ) 00049 plane = False 00050 00051 if plane: 00052 delta = rospy.get_rostime() - time 00053 if delta.to_sec() > 5.0: 00054 rospy.logdebug("Delta of {0} too large.".format(delta.to_sec())) 00055 plane = False 00056 00057 # Next: make sure we aren't over-turning the head. We do this by getting the 00058 # transformation from /base_link (where +x necessarily means "forward") to 00059 # /best_plane, and then looking at the x and y coordinates of that frame. 00060 # In theory, I could use dynamic_reconfigure to set this parameter, but it's 00061 # utterly undocumented, and I'm in a hurry. 00062 if plane: 00063 try: 00064 form = listener.lookupTransform('/base_link', 00065 '/best_plane', 00066 rospy.Time()) 00067 ang = math.atan2(form[0][1], form[0][0]) 00068 if ang > LIMIT or ang < -LIMIT: 00069 rospy.loginfo( 00070 "Got a good delta ({0}) but {1} is outside the range.". 00071 format(delta.to_sec(), ang)) 00072 plane = False 00073 except tf.Exception as e: 00074 rospy.loginfo("Second lookup failure.") 00075 plane = False 00076 00077 if ALWAYS_LOOK_FORWARD: 00078 rospy.loginfo("Always looking forward.") 00079 plane = False 00080 00081 if plane: 00082 rospy.logdebug("Pointing head {0} degrees.".format(math.degrees(ang))) 00083 00084 g = PointHeadGoal() 00085 if plane: 00086 g.target.header.frame_id = '/best_plane' 00087 g.target.point.x = 0.0 00088 g.target.point.y = 0.0 00089 g.target.point.z = 0.0 00090 rospy.logdebug("Pointed the head!") 00091 else: 00092 g.target.header.frame_id = '/base_link' 00093 g.target.point.x = 3.0 00094 g.target.point.y = 0.0 00095 g.target.point.z = 0.0 00096 rospy.logdebug("Forwarded the head!") 00097 g.min_duration = rospy.Duration(1.0) 00098 00099 client.send_goal(g) 00100 client.wait_for_result() 00101 00102 if client.get_state() != GoalStatus.SUCCEEDED: 00103 rospy.loginfo("Whoa! Head pointing failed!")