query_grasps_server.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
4 #
5 # Licensed under the Apache License, Version 2.0 (the "License");
6 # you may not use this file except in compliance with the License.
7 # You may obtain a copy of the License at
8 #
9 # http://www.apache.org/licenses/LICENSE-2.0
10 #
11 # Unless required by applicable law or agreed to in writing, software
12 # distributed under the License is distributed on an "AS IS" BASIS,
13 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 # See the License for the specific language governing permissions and
15 # limitations under the License.
16 
17 
18 import rospy
19 
20 import actionlib
21 import moveit_msgs.msg
22 import cob_grasp_generation.msg
23 from cob_grasp_generation import grasp_query_utils
24 
25 class QueryGraspsServer(object):
26 
27  def __init__(self):
28 
29  self._as_query = actionlib.SimpleActionServer('query_grasps', cob_grasp_generation.msg.QueryGraspsAction, execute_cb=self.query_cb, auto_start = False)
30  self._as_query.start()
31 
32  print("QueryGraspsServer: action started...")
33 
34  def query_cb(self, goal):
35  success = False
36  grasp_list = []
37 
38  rospy.loginfo('Querying grasps for object %s using gripper_type %s' % (goal.object_name, goal.gripper_type))
39 
40  if grasp_query_utils.check_database(goal.object_name, goal.gripper_type):
41  rospy.loginfo('GraspTable for object %s exist in the database.', goal.object_name)
42  rospy.loginfo('Returning grasp list for selected object.')
43  grasp_list = grasp_query_utils.get_grasps(goal.object_name, goal.gripper_type, goal.gripper_side, goal.grasp_id, goal.num_grasps, goal.threshold)
44  else:
45  rospy.logwarn('GraspTable for object %s does not exist!',goal.object_name)
46 
47  if not (grasp_list == []):
48  success = True
49 
50  result = cob_grasp_generation.msg.QueryGraspsResult()
51  result.success = success
52  result.grasp_list = grasp_list
53 
54  if success:
55  rospy.loginfo('Query: Succeeded')
56  self._as_query.set_succeeded(result)
57  else:
58  rospy.logwarn('Query: Failed')
59  self._as_query.set_aborted(result)
60 
61 if __name__ == '__main__':
62  rospy.init_node('query_grasps_server')
64  rospy.spin()


cob_grasp_generation
Author(s): Witalij Siebert, Felix Messmer
autogenerated on Sun Dec 6 2020 03:25:46