00001
00002 import roslib; roslib.load_manifest('ptu_control')
00003 import rospy
00004 import ptu_control.msg
00005 import actionlib
00006 import sys
00007
00008 def ptu_action_test():
00009 client = actionlib.SimpleActionClient('SetPTUState', ptu_control.msg.PtuGotoAction)
00010 client.wait_for_server()
00011 goal = ptu_control.msg.PtuGotoGoal(pan=float(sys.argv[1]), tilt=float(sys.argv[2]))
00012 client.send_goal(goal)
00013 client.wait_for_result()
00014 return client.get_result()
00015
00016 if __name__ == '__main__':
00017 rospy.init_node('action_test')
00018 result = ptu_action_test()
00019 print result