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 from cob_grasp_generation import grasp_query_utils
00024
00025 class QueryGraspsServer(object):
00026
00027 def __init__(self):
00028
00029 self._as_query = actionlib.SimpleActionServer('query_grasps', cob_grasp_generation.msg.QueryGraspsAction, execute_cb=self.query_cb, auto_start = False)
00030 self._as_query.start()
00031
00032 print("QueryGraspsServer: action started...")
00033
00034 def query_cb(self, goal):
00035 success = False
00036 grasp_list = []
00037
00038 rospy.loginfo('Querying grasps for object %s using gripper_type %s' % (goal.object_name, goal.gripper_type))
00039
00040 if grasp_query_utils.check_database(goal.object_name, goal.gripper_type):
00041 rospy.loginfo('GraspTable for object %s exist in the database.', goal.object_name)
00042 rospy.loginfo('Returning grasp list for selected object.')
00043 grasp_list = grasp_query_utils.get_grasps(goal.object_name, goal.gripper_type, goal.gripper_side, goal.grasp_id, goal.num_grasps, goal.threshold)
00044 else:
00045 rospy.logwarn('GraspTable for object %s does not exist!',goal.object_name)
00046
00047 if not (grasp_list == []):
00048 success = True
00049
00050 result = cob_grasp_generation.msg.QueryGraspsResult()
00051 result.success = success
00052 result.grasp_list = grasp_list
00053
00054 if success:
00055 rospy.loginfo('Query: Succeeded')
00056 self._as_query.set_succeeded(result)
00057 else:
00058 rospy.logwarn('Query: Failed')
00059 self._as_query.set_aborted(result)
00060
00061 if __name__ == '__main__':
00062 rospy.init_node('query_grasps_server')
00063 QueryGraspsServer()
00064 rospy.spin()