00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047 package roboearth.wp5;
00048
00049 import java.io.BufferedReader;
00050 import java.io.File;
00051 import java.io.FileReader;
00052 import java.io.FileWriter;
00053 import java.io.IOException;
00054 import java.io.StringReader;
00055 import java.net.URL;
00056 import java.util.ArrayList;
00057 import java.util.Set;
00058
00059 import javax.xml.parsers.ParserConfigurationException;
00060 import javax.xml.parsers.SAXParserFactory;
00061
00062 import org.semanticweb.owlapi.apibinding.OWLManager;
00063 import org.semanticweb.owlapi.model.OWLClass;
00064 import org.semanticweb.owlapi.model.OWLClassExpression;
00065 import org.semanticweb.owlapi.model.OWLDataFactory;
00066 import org.semanticweb.owlapi.model.OWLDataProperty;
00067 import org.semanticweb.owlapi.model.OWLDataPropertyAssertionAxiom;
00068 import org.semanticweb.owlapi.model.OWLIndividual;
00069 import org.semanticweb.owlapi.model.OWLOntology;
00070 import org.semanticweb.owlapi.model.OWLOntologyManager;
00071 import org.semanticweb.owlapi.util.DefaultPrefixManager;
00072 import org.xml.sax.Attributes;
00073 import org.xml.sax.InputSource;
00074 import org.xml.sax.SAXException;
00075 import org.xml.sax.helpers.DefaultHandler;
00076
00077 import roboearth.wp5.conn.REConnectionHadoop;
00078 import roboearth.wp5.owl.OWLIO;
00079 import roboearth.wp5.util.Util;
00080 import ros.NodeHandle;
00081 import ros.Publisher;
00082 import ros.Ros;
00083 import ros.RosException;
00084 import ros.ServiceClient;
00085 import ros.communication.Time;
00086 import ros.pkg.re_msgs.msg.SeenObject;
00087 import ros.pkg.re_srvs.srv.DetectObjects;
00088 import ros.pkg.re_srvs.srv.LoadVslamMap;
00089 import ros.pkg.re_srvs.srv.RoboEarthExportCopModel;
00090 import ros.pkg.re_srvs.srv.RoboEarthRetrieveCopModel;
00091
00092 import com.google.common.base.CaseFormat;
00093 import com.google.common.base.Joiner;
00094
00095
00096 public class REClients {
00097
00098 static Boolean rosInitialized = false;
00099 static Ros ros;
00100 static NodeHandle n;
00101
00102 static final String API_KEY = "6e6574726f6d40b699e442ebdca5850e7cb7486679768aec3c70";
00103
00104
00105
00109 protected static void initRos() {
00110
00111 ros = Ros.getInstance();
00112
00113 if(!ros.isInitialized()) {
00114 ros.init("knowrob_re_client");
00115 }
00116 n = ros.createNodeHandle();
00117
00118 }
00119
00120
00121
00122
00123
00124
00125
00126
00127
00138 public static String[] requestModelFor(String objclass) throws IOException, ParserConfigurationException, SAXException {
00139
00140 String q = "SELECT source FROM CONTEXT source\n" +
00141 "{S} roboearth:providesModelFor {"+objclass.replace("'", "")+"}\n" +
00142 "USING NAMESPACE\n" +
00143 "roboearth=<http://www.roboearth.org/kb/roboearth.owl#>,\n"+
00144 "knowrob=<http://ias.cs.tum.edu/kb/knowrob.owl#>";
00145
00146
00147
00148
00149 String res;
00150 REConnectionHadoop conn = new REConnectionHadoop(API_KEY);
00151
00152 res = conn.queryObjectDB(q);
00153
00154 res = res.replace("\\n", "").replace("\\t", "");
00155 res = res.substring(1, res.length()-1);
00156
00157
00158 ArrayList<String> obj_urls = new ArrayList<String>();
00159 SAXParserFactory factory = SAXParserFactory.newInstance();
00160 factory.setValidating(false);
00161 factory.newSAXParser().parse(new InputSource(new StringReader(res)), new SparqlReader(obj_urls));
00162
00163 return obj_urls.toArray(new String[0]);
00164 }
00165
00166
00167
00168 public static String downloadModelFrom(String url) throws IOException, ParserConfigurationException, SAXException {
00169
00170 ArrayList<String> outFilenames = new ArrayList<String>();
00171 ArrayList<String> outFileURLs = new ArrayList<String>();
00172
00173 REConnectionHadoop conn = new REConnectionHadoop(API_KEY);
00174
00175 String objDir = Util.tmpDir + Util.getFilenameFromURL(url);
00176 String filename = objDir +".owl";
00177
00178 FileWriter out = new FileWriter(filename);
00179 String obj = conn.requestObjectFromURL(url, outFilenames, outFileURLs);
00180 out.write(obj==null?"":obj);
00181 out.close();
00182
00183 if (outFileURLs.size() > 0) {
00184 File dir = new File(objDir);
00185 if (dir.exists()) {
00186 Util.deleteFolderRec(dir, false);
00187 } else {
00188 dir.mkdir();
00189 }
00190
00191 for(int i=0;i<outFileURLs.size();i++) {
00192 conn.requestBinaryFile(new URL(outFileURLs.get(i)), objDir);
00193 }
00194 }
00195
00196
00197
00198
00199 return filename;
00200 }
00201
00202
00203
00204
00205
00206
00207
00208
00219 public static String[] requestActionRecipeFor(String command) throws IOException, ParserConfigurationException, SAXException {
00220
00221
00222 String q = "SELECT source FROM CONTEXT source\n" +
00223 "{S} rdfs:label {\""+command.replace("'", "")+"\"^^xsd:string}\n" +
00224 "USING NAMESPACE\n" +
00225 "rdfs=<http://www.w3.org/2000/01/rdf-schema#>\n";
00226
00227
00228
00229 String res;
00230 REConnectionHadoop conn = new REConnectionHadoop(API_KEY);
00231
00232 res = conn.queryActionRecipeDB(q);
00233
00234 res = res.replace("\\n", "").replace("\\t", "");
00235 res = res.substring(1, res.length()-1);
00236
00237
00238
00239 ArrayList<String> act_urls = new ArrayList<String>();
00240 SAXParserFactory factory = SAXParserFactory.newInstance();
00241 factory.setValidating(false);
00242 factory.newSAXParser().parse(new InputSource(new StringReader(res)), new SparqlReader(act_urls));
00243
00244 return act_urls.toArray(new String[0]);
00245 }
00246
00247
00248 public static String downloadRecipeFrom(String url) throws IOException, ParserConfigurationException, SAXException {
00249
00250
00251
00252 REConnectionHadoop conn = new REConnectionHadoop(API_KEY);
00253 String filename = Util.tmpDir + Util.getFilenameFromURL(url)+".owl";
00254
00255 FileWriter out = new FileWriter(filename);
00256 out.write(conn.requestActionRecipeFromURL(url));
00257 out.close();
00258
00259
00260
00261 return filename;
00262 }
00263
00264
00265
00266
00267
00268
00269
00270
00271
00272
00282 public static String[] requestEnvironmentMapFor(String[][] roomQuery) throws IOException, ParserConfigurationException, SAXException {
00283
00284 String q = "SELECT source FROM CONTEXT source\n" +
00285 "{A} kr:describedInMap {Z} ,\n";
00286
00287 ArrayList<String> constr = new ArrayList<String>();
00288 ArrayList<String> where = new ArrayList<String>();
00289
00290 char idx = 'A';
00291 for(String[] constraint : roomQuery) {
00292
00293 if(idx!='A'){
00294 constr.add("{"+idx+"} kr:properPhysicalParts {"+(char)(idx-1)+"}");
00295 }
00296
00297 String var = constraint[0].split(":")[1];
00298 var = CaseFormat.LOWER_CAMEL.to(CaseFormat.UPPER_CAMEL, var);
00299 var = "V"+var;
00300
00301 constr.add("{"+idx+"} " + constraint[0] + " {"+var+"}");
00302 where.add(var+" LIKE \""+constraint[1]+"\"");
00303
00304 idx++;
00305 }
00306
00307 q+= Joiner.on(" , \n").join(constr);
00308 q+="\nWHERE\n" + Joiner.on("\nAND ").join(where);
00309
00310 q += "\nUSING NAMESPACE\n" +
00311 "re=<http://www.roboearth.org/kb/roboearth.owl#>,\n" +
00312 "rdfs=<http://www.w3.org/2000/01/rdf-schema#>,\n" +
00313 "kr=<http://ias.cs.tum.edu/kb/knowrob.owl#> ";
00314
00315
00316
00317
00318 String res;
00319 REConnectionHadoop conn = new REConnectionHadoop(API_KEY);
00320
00321
00322 res = conn.queryEnvironmentDB(q);
00323
00324 res = res.replace("\\n", "").replace("\\t", "");
00325 res = res.substring(1, res.length()-1);
00326
00327
00328 ArrayList<String> env_urls = new ArrayList<String>();
00329 SAXParserFactory factory = SAXParserFactory.newInstance();
00330 factory.setValidating(false);
00331 factory.newSAXParser().parse(new InputSource(new StringReader(res)), new SparqlReader(env_urls));
00332
00333 return env_urls.toArray(new String[0]);
00334 }
00335
00336
00337 public static String downloadEnvironmentMapFrom(String url, String robotUID, ArrayList<String> outFilenames) throws IOException, ParserConfigurationException, SAXException {
00338
00339 ArrayList<String> outFileURLs = new ArrayList<String>();
00340
00341 REConnectionHadoop conn = new REConnectionHadoop(API_KEY);
00342
00343 String envDir = Util.tmpDir + Util.getFilenameFromURL(url);
00344 String filename = envDir + ".owl";
00345
00346 FileWriter out = new FileWriter(filename);
00347 String env = conn.requestEnvironmentFromURL(url);
00348 if (env != null) {
00349 out.write(env);
00350 out.close();
00351 } else {
00352 System.err.println("Error: environment '" + url + "' couldn't be found.");
00353 return null;
00354 }
00355
00356 File dir = new File(envDir);
00357 if (dir.exists()) {
00358 Util.deleteFolderRec(dir, false);
00359 } else {
00360 dir.mkdir();
00361 }
00362
00363
00364 OWLOntology owlMap = OWLIO.loadOntologyFromFile(filename);
00365 OWLOntologyManager manager = OWLManager.createOWLOntologyManager();
00366 OWLDataFactory factory = manager.getOWLDataFactory();
00367 DefaultPrefixManager pm = new DefaultPrefixManager("http://ias.cs.tum.edu/kb/knowrob.owl#");
00368 pm.setPrefix("knowrob:", "http://ias.cs.tum.edu/kb/knowrob.owl#");
00369 pm.setPrefix("roboearth:", "http://www.roboearth.org/kb/roboearth.owl#");
00370
00371 OWLDataProperty linkToMapFile = factory.getOWLDataProperty("roboearth:linkToMapFile", pm);
00372 OWLDataProperty linkToImageFile = factory.getOWLDataProperty("roboearth:linkToImageFile", pm);
00373 OWLClass octomapCls = factory.getOWLClass("roboearth:OctoMap", pm);
00374
00375 for(OWLIndividual ind : owlMap.getIndividualsInSignature()) {
00376
00377 Set<OWLClassExpression> classExpressions = ind.getTypes(owlMap);
00378 for (OWLClassExpression owlExpr : classExpressions) {
00379
00380
00381 if (owlExpr.asOWLClass().equals(octomapCls)) {
00382
00383
00384 String srdlString = conn.requestRobot(robotUID);
00385 if (srdlString != null && !srdlString.isEmpty()) {
00386 OWLOntology srdl = OWLIO.loadOntologyFromString(srdlString);
00387
00388
00389 String autoMapFilename = "auto_2d_loc_map";
00390 String baseLaserLink = "http://ias.cs.tum.edu/kb/pr2.owl#pr2_base_laser";
00391
00392 ArrayList<byte[]> mapBytes;
00393 mapBytes = conn.request2dMap(Util.getFilenameFromURL(url), srdl, baseLaserLink, autoMapFilename);
00394 if (Util.writeFile(envDir, autoMapFilename+".pgm", mapBytes.get(0))) {
00395 outFilenames.add(envDir + File.separator + autoMapFilename+".pgm");
00396 }
00397 if (Util.writeFile(envDir, autoMapFilename+".yaml", mapBytes.get(1))) {
00398 outFilenames.add(envDir + File.separator + autoMapFilename+".yaml");
00399 }
00400 } else {
00401 System.err.println("Error: Couldn't find robot '" + robotUID + "' in RoboEarthDB ");
00402 }
00403
00404 }
00405
00406 }
00407
00408 for(OWLDataPropertyAssertionAxiom dataprop : owlMap.getDataPropertyAssertionAxioms(ind)) {
00409 if(dataprop.getProperty().equals(linkToMapFile) || dataprop.getProperty().equals(linkToImageFile)) {
00410 String linkUrl = dataprop.getObject().getLiteral().replaceAll("\\s", "");
00411 outFileURLs.add(linkUrl);
00412 }
00413 }
00414
00415 }
00416
00417 for(int i=0;i<outFileURLs.size();i++) {
00418 File outfile = conn.requestBinaryFile(new URL(outFileURLs.get(i)), envDir);
00419 outFilenames.add(outfile.getAbsolutePath());
00420 }
00421
00422
00423 return filename;
00424
00425 }
00426
00427
00428 public static String downloadEnvironmentMapFrom(String url, ArrayList<String> outFilenames) throws IOException, ParserConfigurationException, SAXException {
00429
00430 ArrayList<String> outFileURLs = new ArrayList<String>();
00431
00432 REConnectionHadoop conn = new REConnectionHadoop(API_KEY);
00433
00434 String envDir = Util.tmpDir + Util.getFilenameFromURL(url);
00435 String filename = envDir + ".owl";
00436
00437 FileWriter out = new FileWriter(filename);
00438 out.write(conn.requestEnvironmentFromURL(url));
00439 out.close();
00440
00441
00442 OWLOntology owlMap = OWLIO.loadOntologyFromFile(filename);
00443 OWLOntologyManager manager = OWLManager.createOWLOntologyManager();
00444 OWLDataFactory factory = manager.getOWLDataFactory();
00445 DefaultPrefixManager pm = new DefaultPrefixManager("http://ias.cs.tum.edu/kb/knowrob.owl#");
00446 pm.setPrefix("knowrob:", "http://ias.cs.tum.edu/kb/knowrob.owl#");
00447 pm.setPrefix("roboearth:", "http://www.roboearth.org/kb/roboearth.owl#");
00448
00449 OWLDataProperty linkToMapFile = factory.getOWLDataProperty("roboearth:linkToMapFile", pm);
00450 OWLDataProperty linkToImageFile = factory.getOWLDataProperty("roboearth:linkToImageFile", pm);
00451
00452 for(OWLIndividual ind : owlMap.getIndividualsInSignature()) {
00453 for(OWLDataPropertyAssertionAxiom dataprop : owlMap.getDataPropertyAssertionAxioms(ind)) {
00454
00455 if(dataprop.getProperty().equals(linkToMapFile) || dataprop.getProperty().equals(linkToImageFile)) {
00456 String linkUrl = dataprop.getObject().getLiteral().replaceAll("\\s", "");
00457 outFileURLs.add(linkUrl);
00458 }
00459 }
00460 }
00461
00462 if (outFileURLs.size() > 0) {
00463 File dir = new File(envDir);
00464 if (dir.exists()) {
00465 Util.deleteFolderRec(dir, false);
00466 } else {
00467 dir.mkdir();
00468 }
00469
00470
00471
00472 for(int i=0;i<outFileURLs.size();i++) {
00473 File outfile = conn.requestBinaryFile(new URL(outFileURLs.get(i)), envDir);
00474 outFilenames.add(outfile.getAbsolutePath());
00475 }
00476 }
00477
00478
00479 return filename;
00480
00481 }
00482
00483
00484
00485
00486
00487
00488
00489
00490 public static void submitObject(String owl_filename, String id, String cls, String description) {
00491
00492
00493
00494 REConnectionHadoop conn = new REConnectionHadoop(API_KEY);
00495 boolean res = conn.submitObject(readOWLtoString(owl_filename), cls, id, description);
00496
00497
00498 }
00499
00500
00501 public static void submitActionRecipe(String owl_filename, String id, String cls, String description){
00502
00503
00504
00505 REConnectionHadoop conn = new REConnectionHadoop(API_KEY);
00506 boolean res = conn.submitActionRecipe(readOWLtoString(owl_filename), cls, id, description);
00507
00508
00509 }
00510
00511
00512 public static void submitMap(String owl_filename, String id, String cls, String description){
00513
00514
00515
00516 REConnectionHadoop conn = new REConnectionHadoop(API_KEY);
00517 boolean res = conn.submitEnvironment(readOWLtoString(owl_filename), cls, id, description);
00518
00519
00520 }
00521
00522
00523
00524
00525
00526
00527
00528
00529 public static void updateObjectOWL(String owl_filename, String uid, String description) {
00530
00531
00532
00533 REConnectionHadoop conn = new REConnectionHadoop(API_KEY);
00534 boolean res = conn.updateObject(uid, readOWLtoString(owl_filename), description);
00535
00536
00537 }
00538
00539
00540
00541 public static void updateActionRecipe(String owl_filename, String id, String description) {
00542
00543
00544
00545 REConnectionHadoop conn = new REConnectionHadoop(API_KEY);
00546 boolean res = conn.updateActionRecipe(id, readOWLtoString(owl_filename), description);
00547
00548
00549 }
00550
00551
00552 public static void updateMap(String owl_filename, String id, String description) {
00553
00554
00555
00556 REConnectionHadoop conn = new REConnectionHadoop(API_KEY);
00557 boolean res = conn.updateEnvironment(id, readOWLtoString(owl_filename), description);
00558
00559
00560
00561 }
00562
00563
00564
00565
00566
00567
00568
00569
00570 public static void publishObjectAsSeenObject(Publisher<ros.pkg.re_msgs.msg.SeenObject> pub, String name, float time, String[] pose) {
00571
00572 float[] floatpose = new float[16];
00573
00574 for(int i=0;i<pose.length;i++) {
00575 floatpose[i]=Float.valueOf(pose[i]);
00576 }
00577
00578 publishObjectAsSeenObject(pub, name, time, floatpose);
00579 }
00580
00581 public static Publisher<ros.pkg.re_msgs.msg.SeenObject> startObjPublisher() {
00582
00583 initRos();
00584
00585 try {
00586 return(n.advertise("/vslam/seen_objects", new ros.pkg.re_msgs.msg.SeenObject(), 10));
00587 } catch (RosException e) {
00588 e.printStackTrace();
00589 }
00590 return null;
00591 }
00592
00593 public static void stopObjPublisher(Publisher<ros.pkg.re_msgs.msg.SeenObject> pub) {
00594 pub.shutdown();
00595 }
00596
00597 public static void publishObjectAsSeenObject(Publisher<ros.pkg.re_msgs.msg.SeenObject> pub, String name, float time, float[] pose) {
00598
00599 SeenObject sobj = new SeenObject();
00600 sobj.name = name;
00601 sobj.stamp = new Time(time);
00602
00603 sobj.pose.position.x=pose[3];
00604 sobj.pose.position.y=pose[7];
00605 sobj.pose.position.z=pose[11];
00606
00607 double[] quat = Util.matrixToQuaternion(pose);
00608
00609 sobj.pose.orientation.w=quat[0];
00610 sobj.pose.orientation.x=quat[1];
00611 sobj.pose.orientation.y=quat[2];
00612 sobj.pose.orientation.z=quat[3];
00613
00614
00615
00616 pub.publish(sobj);
00617 ros.spinOnce();
00618 System.err.println("publishing...");
00619
00620 }
00621
00622
00623
00624
00625
00626
00627
00628
00629
00630 public static boolean requestCopModel(String object_name) {
00631
00632 try{
00633
00634 initRos();
00635
00636 RoboEarthRetrieveCopModel.Request req = new RoboEarthRetrieveCopModel.Request();
00637 req.object_name = object_name;
00638
00639 ServiceClient<RoboEarthRetrieveCopModel.Request, RoboEarthRetrieveCopModel.Response,
00640 RoboEarthRetrieveCopModel> cl =
00641 n.serviceClient("/re_cop_interface/retrieveCopModelByName",
00642 new RoboEarthRetrieveCopModel());
00643
00644 RoboEarthRetrieveCopModel.Response res = cl.call(req);
00645
00646
00647
00648 cl.shutdown();
00649
00650 if(res.success==1)
00651 return true;
00652 else
00653 return false;
00654
00655 } catch (RosException e) {
00656 e.printStackTrace();
00657 }
00658 return false;
00659 }
00660
00666 public static boolean exportCopModel(int obj_id) {
00667
00668 try{
00669
00670 initRos();
00671
00672 RoboEarthExportCopModel.Request req = new RoboEarthExportCopModel.Request();
00673 req.object_id = obj_id;
00674
00675 ServiceClient<RoboEarthExportCopModel.Request, RoboEarthExportCopModel.Response,
00676 RoboEarthExportCopModel> cl =
00677 n.serviceClient("/re_cop_interface/exportCopModel",
00678 new RoboEarthExportCopModel());
00679
00680 RoboEarthExportCopModel.Response res = cl.call(req);
00681 cl.shutdown();
00682
00683 if(res.success==1)
00684 return true;
00685 else
00686 return false;
00687
00688 } catch (RosException e) {
00689 e.printStackTrace();
00690 }
00691 return false;
00692 }
00693
00694
00695
00696
00697
00705 public static boolean updateVslamMaps(String map_url) {
00706
00707
00708 if (map_url != null) {
00709
00710 try {
00711
00712 initRos();
00713
00714 String uid = Util.getFilenameFromURL(map_url);
00715 LoadVslamMap.Request req = new LoadVslamMap.Request();
00716 req.mapUID = uid;
00717
00718 ServiceClient<LoadVslamMap.Request, LoadVslamMap.Response, LoadVslamMap> cl;
00719 cl = n.serviceClient("/vslam/load_uid_vmap", new LoadVslamMap());
00720
00721 LoadVslamMap.Response res = cl.call(req);
00722 cl.shutdown();
00723
00724 if(res.success)
00725 return true;
00726
00727 else
00728 return false;
00729
00730 } catch (RosException e) {
00731 e.printStackTrace();
00732 }
00733
00734 }
00735
00736 return false;
00737
00738 }
00739
00740
00741
00742
00743
00753 public static boolean updateObjectModels(String[] filenames) {
00754
00755 if (filenames != null) {
00756
00757 try {
00758
00759 initRos();
00760
00761 ArrayList<String> inputUIDs = new ArrayList<String>();
00762 DetectObjects.Request req = new DetectObjects.Request();
00763 req.uids = new ArrayList<String>();
00764
00765 for (String filename : filenames) {
00766
00767
00768
00769 String uid = Util.getFilenameFromURL(filename);
00770 uid = uid.substring(0, uid.length()-4);
00771
00772 inputUIDs.add(uid);
00773 req.uids.add(uid);
00774 }
00775
00776 System.err.println(req.uids.toString());
00777
00778 ServiceClient<DetectObjects.Request, DetectObjects.Response, DetectObjects> cl;
00779 cl = n.serviceClient("/vslam/load_objects", new DetectObjects());
00780
00781 DetectObjects.Response res = cl.call(req);
00782 cl.shutdown();
00783
00784
00785 for (String outputUID : res.detectableUIDs) {
00786 for (String inputUID : inputUIDs) {
00787 if (inputUID.equals(outputUID)) {
00788 inputUIDs.remove(outputUID);
00789 break;
00790 }
00791 }
00792 }
00793
00794 if (inputUIDs.size() == 0) {
00795 return true;
00796 } else {
00797
00798 for (String notFoundUID : inputUIDs) {
00799 System.out.println("Warning: object model '"
00800 + notFoundUID + "' couldn't be found!");
00801 }
00802
00803 return false;
00804 }
00805
00806 } catch (RosException e) {
00807 e.printStackTrace();
00808 }
00809
00810 }
00811
00812 return false;
00813
00814 }
00815
00816
00817
00818
00819
00820
00821 public static void resetDBcontent() {
00822
00823 System.out.println("Updating bedrecmodel");
00824 updateObjectOWL("/home/tenorth/re-obj-models/bed/bed.owl", "bedrecmodel.bedrecmodel", "");
00825
00826 System.out.println("Updating bottlerecmodel");
00827 updateObjectOWL("/home/tenorth/re-obj-models/bottle/bottle.owl", "bottlerecmodel.bottlerecmodel", "");
00828
00829 System.out.println("Updating expedit");
00830 updateObjectOWL("/home/tenorth/re-obj-models/expedit/expedit.owl", "cabinet.ikeaexpedit2x4", "");
00831
00832
00833
00834
00835
00836
00837 }
00838
00839
00840
00841
00842
00843
00844
00848 private static class SparqlReader extends DefaultHandler {
00849
00850 private ArrayList<String> urls;
00851
00852 public SparqlReader(ArrayList<String> urls) {
00853 this.urls = urls;
00854 }
00855
00856 protected boolean uri = false;
00857 public void startElement(String uri, String name, String qName, Attributes attrs) {
00858 if(qName.equals("uri")) {
00859 this.uri = true;
00860 }
00861 }
00862
00863 @Override
00864 public void characters( char[] ch, int start, int length ) {
00865
00866 if(uri) {
00867 urls.add(new String(ch).substring(start, start+length));
00868 this.uri=false;
00869 }
00870 }
00871 }
00872
00873
00874
00875
00876 private static String readOWLtoString(String owl_filename) {
00877
00878 String objectOwl = "";
00879 try {
00880 BufferedReader reader = new BufferedReader( new FileReader (new File(owl_filename)));
00881 String line = null;
00882
00883 while( ( line = reader.readLine() ) != null ) {
00884 objectOwl+= line + System.getProperty("line.separator");
00885 }
00886 } catch (IOException e) {
00887 e.printStackTrace();
00888 }
00889 return objectOwl;
00890 }
00891 }