$search
00001 #! /usr/bin/env python 00002 00003 import roslib; roslib.load_manifest('busbots_unloader') 00004 import rospy 00005 import actionlib 00006 from pr2_controllers_msgs.msg import PointHeadAction, PointHeadGoal 00007 from object_manipulator.convert_functions import * 00008 from geometry_msgs.msg import * 00009 00010 def point_head(): 00011 client = actionlib.SimpleActionClient('/head_traj_controller/point_head_action', PointHeadAction) 00012 00013 # Waits until the action server has started up and started 00014 # listening for goals. 00015 client.wait_for_server() 00016 00017 # Creates a goal to send to the action server. 00018 point = [0., 0, 0] 00019 point_frame = '/l_wrist_roll_link' 00020 axis = [1, 0, 0] 00021 axis_frame = '/high_def_frame' 00022 point_head_goal = PointHeadGoal() 00023 point_head_goal.target = create_point_stamped(point, point_frame) 00024 #point_head_goal.pointing_frame = axis_frame 00025 #point_head_goal.pointing_axis = Vector3(*axis) 00026 point_head_goal.max_velocity = 1.0 00027 00028 print"Pointing",axis_frame, pplist(axis), "at", point_frame, pplist(point) 00029 # Sends the goal to the action server. 00030 client.send_goal(point_head_goal) 00031 00032 # Waits for the server to finish performing the action. 00033 client.wait_for_result() 00034 00035 00036 if __name__ == '__main__': 00037 rospy.init_node('point_head_test') 00038 point_head() 00039 00040