head_down.py
Go to the documentation of this file.
1 #! /usr/bin/python
2 import roslib
3 roslib.load_manifest('pr2_position_scripts')
4 
5 import rospy
6 import actionlib
7 from actionlib_msgs.msg import *
8 from pr2_controllers_msgs.msg import *
9 from geometry_msgs.msg import *
10 
11 rospy.init_node('move_the_head', anonymous=True)
12 
13 client = actionlib.SimpleActionClient('/head_traj_controller/point_head_action', PointHeadAction)
14 client.wait_for_server()
15 
16 g = PointHeadGoal()
17 g.target.header.frame_id = 'base_link'
18 g.target.point.x = 1.0
19 g.target.point.y = 0.0
20 g.target.point.z = 0.0
21 g.min_duration = rospy.Duration(1.0)
22 
23 client.send_goal(g)
24 client.wait_for_result()
25 
26 if client.get_state() == GoalStatus.SUCCEEDED:
27  print "Succeeded"
28 else:
29  print "Failed"


pr2_position_scripts
Author(s): Tony Pratkanis
autogenerated on Thu Jun 6 2019 19:18:45