Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031 PKG = "pr2_mechanism_controllers"
00032
00033 import roslib; roslib.load_manifest(PKG)
00034
00035 import sys
00036 import os
00037 import string
00038 from time import sleep
00039
00040 import rospy
00041 from geometry_msgs.msg import PointStamped, Point
00042 from sensor_msgs.msg import JointState
00043
00044 def point_head_client(pan, tilt):
00045
00046 head_angles = rospy.Publisher('head_controller/command', JointState)
00047 rospy.init_node('head_commander', anonymous=True)
00048 sleep(1)
00049 js = JointState()
00050 js.name = ['head_pan_joint', 'head_tilt_joint'];
00051 js.position = [pan,tilt];
00052 head_angles.publish(js)
00053 sleep(1)
00054
00055 def point_head_cart_client(x,y,z,frame):
00056
00057 head_angles = rospy.Publisher('head_controller/point_head', PointStamped)
00058 rospy.init_node('head_commander', anonymous=True)
00059 sleep(1)
00060 head_angles.publish(PointStamped(rospy.Header(None, rospy.get_rostime(), frame), Point(x, y, z)))
00061 sleep(1)
00062
00063
00064 def usage():
00065 return "%s [pan tilt] or [x,y,z,frame]"%sys.argv[0]
00066
00067 if __name__ == "__main__":
00068
00069 if len(sys.argv) < 3:
00070 print usage()
00071 sys.exit(1)
00072 elif len(sys.argv) ==3:
00073 point_head_client(float(sys.argv[1]), float(sys.argv[2]))
00074 elif len(sys.argv) ==5:
00075 point_head_cart_client(float(sys.argv[1]), float(sys.argv[2]), float(sys.argv[3]), sys.argv[4])