Go to the documentation of this file.00001
00002 import roslib
00003 roslib.load_manifest('pr2_gazebo_benchmarks')
00004
00005 import sys
00006 import rospy
00007 import actionlib
00008 from actionlib_msgs.msg import *
00009 from pr2_controllers_msgs.msg import *
00010
00011 rospy.init_node('single_joint_position', anonymous=True)
00012 gripper_action_topic = sys.argv[1]+'_gripper_controller/gripper_action'
00013 client = actionlib.SimpleActionClient(gripper_action_topic,
00014 Pr2GripperCommandAction)
00015 client.wait_for_server()
00016
00017 goal = Pr2GripperCommandGoal();
00018 goal.command.position = float(sys.argv[2])
00019 goal.command.max_effort = float(sys.argv[3])
00020 client.send_goal(goal)
00021 client.wait_for_result()
00022 if client.get_state() == GoalStatus.SUCCEEDED:
00023 print "Success"