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 or_grasp_generation, grasp_query_utils
00024
00025 class GenerateGraspsServer(object):
00026
00027 def __init__(self):
00028 self.orgg = or_grasp_generation.ORGraspGeneration()
00029
00030 self._as_generate = actionlib.SimpleActionServer('generate_grasps', cob_grasp_generation.msg.GenerateGraspsAction, execute_cb=self.generate_cb, auto_start = False)
00031 self._as_generate.start()
00032
00033 print("GenerateGraspsServer: action started...")
00034
00035 def generate_cb(self, goal):
00036 success = False
00037 num_grasps = 0
00038
00039 rospy.loginfo('Generating grasps for object %s using gripper_type %s' % (goal.object_name, goal.gripper_type))
00040
00041 if grasp_query_utils.check_database(goal.object_name, goal.gripper_type):
00042 rospy.logwarn('Grasps for object %s exist in the database.', goal.object_name)
00043 success = False
00044 else:
00045 self.orgg.setup_environment(goal.object_name, goal.gripper_type, goal.viewer)
00046 rospy.loginfo('GraspTable for object %s does not exist. Now planning Grasps for the object',goal.object_name)
00047 num_grasps = self.orgg.generate_grasps(goal.object_name, goal.gripper_type, goal.replan)
00048 if (num_grasps > 0):
00049 success = True
00050
00051 result = cob_grasp_generation.msg.GenerateGraspsResult()
00052 result.success = success
00053 result.num_grasps = num_grasps
00054
00055 if success:
00056 rospy.loginfo('Generate: Succeeded')
00057 self._as_generate.set_succeeded(result)
00058 else:
00059 rospy.logwarn('Generate: Failed')
00060 self._as_generate.set_aborted(result)
00061
00062
00063 if __name__ == '__main__':
00064 rospy.init_node('generate_grasps_server')
00065 GenerateGraspsServer()
00066 rospy.spin()