$search
00001 #!/usr/bin/env python 00002 import roslib; 00003 roslib.load_manifest('srs_knowledge') 00004 import sys 00005 import rospy 00006 00007 from srs_knowledge.srv import * 00008 from srs_knowledge.msg import * 00009 from srs_msgs.msg import * 00010 00011 def getObjectsOnMap(): 00012 print 'test get all objects from map' 00013 try: 00014 getObjects = rospy.ServiceProxy('get_objects_on_map', GetObjectsOnMap) 00015 res = getObjects('ipa-kitchen-map', True) 00016 return res 00017 except rospy.ServiceException, e: 00018 print "Service call failed: %s"%e 00019 00020 def getWorkspaceOnMap(): 00021 print 'test get all workspace (furnitures basically here) from map' 00022 try: 00023 getWorkspace = rospy.ServiceProxy('get_workspace_on_map', GetWorkspaceOnMap) 00024 res = getWorkspace('ipa-kitchen-map', True) 00025 return res 00026 except rospy.ServiceException, e: 00027 print "Service call failed: %s"%e 00028 00029 00030 def updatePosInfo(): 00031 print 'update spatial info' 00032 try: 00033 posInfo = SRSSpatialInfo() 00034 posInfo.pose.position.x = 0.65 00035 posInfo.pose.position.y = 1.21 00036 posInfo.pose.position.z = 0.1 00037 posInfo.pose.orientation.x = 0 00038 posInfo.pose.orientation.y = 0 00039 posInfo.pose.orientation.z = 0 00040 posInfo.pose.orientation.w = 1 00041 00042 posInfo.l = 0.9 00043 posInfo.h = 0.9 00044 posInfo.w = 0.74 00045 00046 updatePos = rospy.ServiceProxy('update_pos_info', UpdatePosInfo) 00047 res = updatePos('Table0', 7, posInfo, 'not used') 00048 return res 00049 except rospy.ServiceException, e: 00050 print "Service call failed: %s"%e 00051 00052 00053 def insertObject(): 00054 print 'update spatial info' 00055 try: 00056 insertObj = rospy.ServiceProxy('insert_instance', InsertInstance) 00057 res = insertObj('Table0', 'Table-PieceOfFurniture', '7', 'not used', 'not used') 00058 return res 00059 except rospy.ServiceException, e: 00060 print "Service call failed: %s"%e 00061 00062 def insertMilkbox(): 00063 print 'update spatial info' 00064 try: 00065 insertObj = rospy.ServiceProxy('insert_instance', InsertInstance) 00066 res = insertObj('MilkBox0', 'Milkbox', '9', 'not used', 'not used') 00067 return res 00068 except rospy.ServiceException, e: 00069 print "Service call failed: %s"%e 00070 00071 if __name__ == "__main__": 00072 # print getObjectsOnMap() 00073 # print getWorkspaceOnMap() 00074 print insertObject() 00075 print updatePosInfo() 00076 print insertMilkbox()