Go to the documentation of this file.00001
00002 import roslib;
00003
00004 roslib.load_manifest('srs_knowledge')
00005 roslib.load_manifest('geometry_msgs')
00006 import sys
00007 import rospy
00008 from geometry_msgs.msg import *
00009
00010 from srs_knowledge.srv import *
00011
00012 def querySparQL():
00013 rospy.wait_for_service('query_sparql')
00014 try:
00015 print '\n---- Try SparQL to query all instances of type Table ----'
00016 spql = rospy.ServiceProxy('query_sparql', QuerySparQL)
00017 queryString = "PREFIX house: <http://www.semanticweb.org/ontologies/house.owl#> PREFIX rdf: <http://www.w3.org/1999/02/22-rdf-syntax-ns#> \n SELECT ?table \n WHERE { ?table rdf:type house:Table . }"
00018 print queryString
00019 print '----\n'
00020 resp1 = spql(queryString)
00021 return resp1.result
00022 except rospy.ServiceException, e:
00023 print "Service call failed: %s"%e
00024
00025
00026 def queryGripper():
00027 rospy.wait_for_service('query_sparql')
00028 try:
00029 print '\n---- Try SparQL to query all instances of type Table ----'
00030 spql = rospy.ServiceProxy('query_sparql', QuerySparQL)
00031
00032 queryString = """
00033 PREFIX srs: <http://www.srs-project.eu/ontologies/srs.owl#>
00034 PREFIX rdf: <http://www.w3.org/1999/02/22-rdf-syntax-ns#>
00035 PREFIX ipa-kitchen-map: <http://www.srs-project.eu/ontologies/ipa-kitchen-map.owl#>
00036 SELECT ?gripper WHERE {
00037 ipa-kitchen-map:cob3-3 srs:hasPart ?gripper .
00038 ?gripper a srs:RobotGripper .
00039 }
00040 """
00041 print queryString
00042 print '----\n'
00043 resp1 = spql(queryString)
00044 return resp1.result
00045 except rospy.ServiceException, e:
00046 print "Service call failed: %s"%e
00047
00048 def queryGrippedBy():
00049 rospy.wait_for_service('query_sparql')
00050 try:
00051 print '\n---- Try SparQL to query all instances of type Table ----'
00052 spql = rospy.ServiceProxy('query_sparql', QuerySparQL)
00053
00054 queryString = """
00055 PREFIX srs: <http://www.srs-project.eu/ontologies/srs.owl#>
00056 PREFIX rdf: <http://www.w3.org/1999/02/22-rdf-syntax-ns#>
00057 PREFIX ipa-kitchen-map: <http://www.srs-project.eu/ontologies/ipa-kitchen-map.owl#>
00058 SELECT ?gripper ?type WHERE {
00059 ipa-kitchen-map:MilkBox0 srs:spatiallyRelated ?gripper .
00060 }
00061 """
00062 print queryString
00063 print '----\n'
00064 resp1 = spql(queryString)
00065 return resp1.result
00066 except rospy.ServiceException, e:
00067 print "Service call failed: %s"%e
00068
00069 def queryGetWorkspace():
00070 rospy.wait_for_service('query_sparql')
00071 try:
00072 print '\n---- Try SparQL to query all instances of type Table ----'
00073 spql = rospy.ServiceProxy('query_sparql', QuerySparQL)
00074
00075 queryString = """
00076 PREFIX srs: <http://www.srs-project.eu/ontologies/srs.owl#>
00077 PREFIX rdf: <http://www.w3.org/1999/02/22-rdf-syntax-ns#>
00078 PREFIX ipa-kitchen-map: <http://www.srs-project.eu/ontologies/ipa-kitchen-map.owl#>
00079 PREFIX rdfs: <http://www.w3.org/2000/01/rdf-schema#>
00080 SELECT ?ws ?rel ?obj WHERE {
00081 ?obj srs:spatiallyRelated ipa-kitchen-map:SRSCOBTray .
00082 }
00083 """
00084 print queryString
00085 print '----\n'
00086 resp1 = spql(queryString)
00087 return resp1.result
00088 except rospy.ServiceException, e:
00089 print "Service call failed: %s"%e
00090
00091
00092 def queryGetObjOnWorkspace():
00093 rospy.wait_for_service('query_sparql')
00094 try:
00095 print '\n---- Try SparQL to query all instances of type Table ----'
00096 spql = rospy.ServiceProxy('query_sparql', QuerySparQL)
00097
00098 queryString = """
00099 PREFIX srs: <http://www.srs-project.eu/ontologies/srs.owl#>
00100 PREFIX rdf: <http://www.w3.org/1999/02/22-rdf-syntax-ns#>
00101 PREFIX ipa-kitchen-map: <http://www.srs-project.eu/ontologies/ipa-kitchen-map.owl#>
00102 PREFIX rdfs: <http://www.w3.org/2000/01/rdf-schema#>
00103 SELECT DISTINCT ?obj WHERE {
00104 ?obj srs:spatiallyRelated ipa-kitchen-map:Dishwasher0 .
00105 ?obj a srs:Milkbox .
00106 }
00107 """
00108
00109 print queryString
00110 print '----\n'
00111 resp1 = spql(queryString)
00112 return resp1.result
00113 except rospy.ServiceException, e:
00114 print "Service call failed: %s"%e
00115
00116
00117 def testNextActionService(result):
00118 print 'Plan next Action service'
00119 rospy.wait_for_service('plan_next_action')
00120 try:
00121 next_action = rospy.ServiceProxy('plan_next_action', PlanNextAction)
00122
00123 resp1 = next_action(1, result)
00124
00125 return resp1.nextAction
00126
00127 except rospy.ServiceException, e:
00128 print "Service call failed: %s"%e
00129
00130 def terminateCurrentTask():
00131 print 'Terminate current task (due to vital problems, e.g. with hardware)'
00132 rospy.wait_for_service('plan_next_action')
00133 try:
00134 next_action = rospy.ServiceProxy('plan_next_action', PlanNextAction)
00135 res = next_action(1, [2, 2, 2])
00136 return res
00137 except rospy.ServiceException, e:
00138 print "Service call failed: %s"%e
00139
00140 def requestNewTask():
00141 print 'Request new task'
00142 rospy.wait_for_service('task_request')
00143 try:
00144 p = Pose2D()
00145 p.x = 1
00146 p.y = 1
00147 p.theta = 0
00148 requestNewTask = rospy.ServiceProxy('task_request', TaskRequest)
00149 res = requestNewTask('get', 'MilkBox', None)
00150 return res
00151 except rospy.ServiceException, e:
00152 print "Service call failed: %s"%e
00153
00154
00155 def querySuperClasses():
00156 rospy.wait_for_service('query_sparql')
00157 try:
00158 print '\n---- Try SparQL to query all instances of type Table ----'
00159 spql = rospy.ServiceProxy('query_sparql', QuerySparQL)
00160
00161 queryString = """
00162 PREFIX srs: <http://www.srs-project.eu/ontologies/srs.owl#>
00163 PREFIX rdf: <http://www.w3.org/1999/02/22-rdf-syntax-ns#>
00164 PREFIX ipa-kitchen-map: <http://www.srs-project.eu/ontologies/ipa-kitchen-map.owl#>
00165 PREFIX rdfs: <http://www.w3.org/2000/01/rdf-schema#>
00166 SELECT ?sup WHERE {
00167 srs:Milkbox rdfs:subClassOf ?sup .
00168 ?sup rdfs:subClassOf srs:GraspableObject .
00169 }
00170 """
00171 print queryString
00172 print '----\n'
00173 resp1 = spql(queryString)
00174 return resp1.result
00175 except rospy.ServiceException, e:
00176 print "Service call failed: %s"%e
00177
00178 if __name__ == "__main__":
00179 print querySparQL()
00180 print queryGripper()
00181 print queryGrippedBy()
00182 print queryGetWorkspace()
00183 print queryGetObjOnWorkspace()
00184 print querySuperClasses()
00185
00186
00187
00188
00189
00190