head_up.py
Go to the documentation of this file.
00001 #! /usr/bin/python
00002 import roslib
00003 roslib.load_manifest('pr2_position_scripts')
00004 
00005 import rospy
00006 import actionlib
00007 from actionlib_msgs.msg import *
00008 from pr2_controllers_msgs.msg import *
00009 from geometry_msgs.msg import *
00010  
00011 rospy.init_node('move_the_head', anonymous=True)
00012  
00013 client = actionlib.SimpleActionClient('/head_traj_controller/point_head_action', PointHeadAction)
00014 client.wait_for_server()
00015 
00016 g = PointHeadGoal()
00017 g.target.header.frame_id = 'head_pan_link'
00018 g.target.point.x = 1.0
00019 g.target.point.y = 0.0
00020 g.target.point.z = 0.0
00021 g.min_duration = rospy.Duration(1.0)
00022 
00023 client.send_goal(g)
00024 client.wait_for_result()
00025 
00026 if client.get_state() == GoalStatus.SUCCEEDED:
00027     print "Succeeded"
00028 else:
00029     print "Failed"


pr2_position_scripts
Author(s): Tony Pratkanis
autogenerated on Thu Nov 28 2013 11:38:14