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 query_grasps_client():
00025 client = actionlib.SimpleActionClient('query_grasps', cob_grasp_generation.msg.QueryGraspsAction)
00026 client.wait_for_server()
00027
00028 goal = cob_grasp_generation.msg.QueryGraspsGoal()
00029
00030
00031 goal.object_name="pringles"
00032 goal.gripper_type = "sdhx"
00033
00034 goal.num_grasps = 0
00035 goal.threshold = 0
00036
00037 client.send_goal(goal)
00038 client.wait_for_result()
00039 return client.get_result()
00040
00041 if __name__ == '__main__':
00042 try:
00043 rospy.init_node('query_grasps_client')
00044 result = query_grasps_client()
00045 print "Result:"
00046 print result
00047
00048 except rospy.ROSInterruptException:
00049 print "program interrupted before completion"