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 from cob_grasp_generation import or_grasp_generation, grasp_query_utils
00023
00024 class ShowGraspsOrServer(object):
00025
00026 def __init__(self):
00027 self.orgg = or_grasp_generation.ORGraspGeneration()
00028
00029 self._as_show = actionlib.SimpleActionServer('show_grasps_or', cob_grasp_generation.msg.ShowGraspsAction, execute_cb=self.show_cb, auto_start = False)
00030 self._as_show.start()
00031
00032 print("ShowGraspsOrServer: action started...")
00033
00034
00035 def show_cb(self, goal):
00036 success = False
00037
00038 rospy.loginfo('Show grasp %i for object %s using gripper_type %s' % (goal.grasp_id, goal.object_name, goal.gripper_type))
00039
00040 if grasp_query_utils.check_database(goal.object_name, goal.gripper_type):
00041 self.orgg.setup_environment(goal.object_name, goal.gripper_type, viewer=True)
00042 rospy.loginfo('Display Grasp. Object: %s | ID: %i' % (goal.object_name, goal.grasp_id))
00043 self.orgg.show_grasp(goal.object_name, goal.gripper_type, goal.grasp_id, goal.sort_by_quality)
00044 success = True
00045 else:
00046 rospy.logerr('GraspTable for Object %s does not exist!' % (goal.object_name))
00047
00048 result = cob_grasp_generation.msg.ShowGraspsResult()
00049 result.success = success
00050
00051 if success:
00052 rospy.loginfo('Show: Succeeded')
00053 self._as_show.set_succeeded(result)
00054 else:
00055 rospy.logwarn('Show: Failed')
00056 self._as_show.set_aborted(result)
00057
00058
00059 if __name__ == '__main__':
00060 rospy.init_node('show_grasps_or_server')
00061 ShowGraspsOrServer()
00062 rospy.spin()