$search
00001 #!/usr/bin/env python 00002 00003 import roslib; roslib.load_manifest('srs_object_verification'); 00004 import rospy 00005 00006 from srs_semantics_db.srv import * 00007 from srs_semantics_db.msg import * 00008 from gdatabase.srv import * 00009 from geometry_msgs.msg import * 00010 00011 def list_service_cb(req): 00012 if req.tbox_class.class_id != 1: 00013 print "Object class not supported" 00014 return False 00015 table1 = ABoxObject() 00016 table1.object_id = 0 00017 table2 = ABoxObject() 00018 table2.object_id = 1 00019 res = ListInstancesOfClassResponse() 00020 res.list = [table1,table2] 00021 return res 00022 00023 def info_service_cb(req): 00024 res = GetInfoObjectResponse() 00025 if req.objectID == 0: 00026 res.objectName = "kitchen" 00027 res.objectPose = Pose(position=Point(-3.2,0.055,0.9), orientation=Quaternion(0,0,0,0)) 00028 res.classID = 1 00029 elif req.objectID == 1: 00030 res.objectName = "table1" 00031 res.objectPose = Pose(position=Point(0.67,1.26,0.74), orientation=Quaternion(0,0,0,0)) 00032 res.classID = 1 00033 else: 00034 print "Object info not found" 00035 return False 00036 return res 00037 00038 def start_server(): 00039 rospy.init_node('semantic_db_test_server') 00040 s = rospy.Service('list_all_instances_of_class', ListInstancesOfClass, list_service_cb) 00041 s = rospy.Service('get_info_object', GetInfoObject, info_service_cb) 00042 print "Ready to return objects from db." 00043 rospy.spin() 00044 00045 if __name__ == "__main__": 00046 start_server()