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