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 import rospy
00019
00020 import actionlib
00021 import moveit_msgs.msg
00022 import cob_grasp_generation.msg
00023
00024 def show_grasps_client():
00025 client = actionlib.SimpleActionClient('show_grasps_or', cob_grasp_generation.msg.ShowGraspsAction)
00026 client.wait_for_server()
00027
00028
00029
00030 object_name = "yellowsaltcube"
00031 grasp_id = 0
00032
00033 gripper_type = "sdh"
00034
00035 while not rospy.is_shutdown():
00036 print grasp_id
00037
00038
00039 goal = cob_grasp_generation.msg.ShowGraspsGoal(object_name, gripper_type, grasp_id, True)
00040
00041 client.send_goal(goal)
00042 client.wait_for_result()
00043 success = client.get_result().success
00044 if not success:
00045 break
00046
00047 raw_input("Enter for next grasp...")
00048 grasp_id = grasp_id + 1
00049
00050 print "no more grasps"
00051
00052
00053 if __name__ == '__main__':
00054 try:
00055 rospy.init_node('show_grasp_client')
00056 result = show_grasps_client()
00057 except rospy.ROSInterruptException:
00058 print "program interrupted before completion"