$search
00001 package edu.tum.cs.ias.knowrob.map; 00002 00003 import java.io.*; 00004 import java.util.Date; 00005 import java.util.ArrayList; 00006 import java.util.HashMap; 00007 import java.text.SimpleDateFormat; 00008 import org.semanticweb.owlapi.apibinding.OWLManager; 00009 import org.semanticweb.owlapi.io.RDFXMLOntologyFormat; 00010 import org.semanticweb.owlapi.model.*; 00011 import org.semanticweb.owlapi.util.DefaultPrefixManager; 00012 import org.semanticweb.owlapi.vocab.PrefixOWLOntologyFormat; 00013 import ros.*; 00014 import ros.pkg.geometry_msgs.msg.Point; 00015 import ros.pkg.geometry_msgs.msg.Quaternion; 00016 00017 00018 00019 00020 // 00021 // 00022 // export trajectory points to OWL 00023 // 00024 // 00025 00026 00027 00028 public class PosesToOWL { 00029 00030 00032 // Set IRIs for the ontologies used here 00033 // 00034 00035 // Base IRI for KnowRob ontology 00036 public final static String KNOWROB = "http://ias.cs.tum.edu/kb/knowrob.owl#"; 00037 00038 // Base IRI for OWL ontology 00039 public final static String OWL = "http://www.w3.org/2002/07/owl#"; 00040 00041 // Base IRI for RDFS 00042 public final static String RDFS = "http://www.w3.org/2000/01/rdf-schema#"; 00043 00044 // Base IRI for semantic map ontology 00045 public final static String IAS_MAP = "http://ias.cs.tum.edu/kb/ccrl2_semantic_map_addons.owl#"; 00046 00047 00048 // Prefix manager 00049 public final static DefaultPrefixManager PREFIX_MANAGER = new DefaultPrefixManager(IAS_MAP); 00050 static { 00051 PREFIX_MANAGER.setPrefix("knowrob:", KNOWROB); 00052 PREFIX_MANAGER.setPrefix("ias_map:", IAS_MAP); 00053 PREFIX_MANAGER.setPrefix("owl:", OWL); 00054 PREFIX_MANAGER.setPrefix("rdfs:", RDFS); 00055 } 00056 00057 // mapping ROS-KnowRob identifiers 00058 protected static final HashMap<String, String> rosToKnowrob = new HashMap<String, String>(); 00059 static { 00060 rosToKnowrob.put("cupboard", "knowrob:Cupboard"); 00061 rosToKnowrob.put("drawer", "knowrob:Drawer"); 00062 rosToKnowrob.put("oven", "knowrob:Oven"); 00063 rosToKnowrob.put("refrigerator", "knowrob:Refrigerator"); 00064 rosToKnowrob.put("dishwasher", "knowrob:Dishwasher"); 00065 rosToKnowrob.put("table", "knowrob:Table"); 00066 rosToKnowrob.put("countertop", "knowrob:CounterTop"); 00067 rosToKnowrob.put("sink", "knowrob:Sink"); 00068 rosToKnowrob.put("door", "knowrob:Door"); 00069 rosToKnowrob.put("hinge", "knowrob:HingedJoint"); 00070 rosToKnowrob.put("handle", "knowrob:Handle"); 00071 rosToKnowrob.put("knob", "knowrob:ControlKnob"); 00072 00073 // TODO: add a concept for horizontal planes to knowrob 00074 rosToKnowrob.put("horizontal_plane", "knowrob:CounterTop"); 00075 } 00076 00077 HashMap<String, ArrayList<OWLNamedIndividual>> pointsInTrajectories; 00078 00079 OWLDataFactory factory; 00080 OWLOntologyManager manager; 00081 DefaultPrefixManager pm; 00082 00083 int inst_counter=150; // counter to create unique instance identifiers 00084 00086 // ROS stuff 00087 00088 static Boolean rosInitialized = false; 00089 static Ros ros; 00090 static NodeHandle n; 00091 00093 00094 00100 protected static void initRos(String node_name) { 00101 00102 ros = Ros.getInstance(); 00103 00104 if(!Ros.getInstance().isInitialized()) { 00105 ros.init(node_name); 00106 } 00107 n = ros.createNodeHandle(); 00108 00109 } 00110 00117 public PosesToOWL() { 00118 00119 pointsInTrajectories = new HashMap<String, ArrayList<OWLNamedIndividual>>(); 00120 00121 initRos("bla"); 00122 00123 } 00124 00125 00131 public OWLOntology buildOWLDescription(String filename) { 00132 00133 OWLOntology ontology = null; 00134 pointsInTrajectories.clear(); 00135 00136 00137 00138 try{ 00139 00140 BufferedReader reader = new BufferedReader(new FileReader(filename)); 00141 00142 // Create ontology manager and data factory 00143 manager = OWLManager.createOWLOntologyManager(); 00144 factory = manager.getOWLDataFactory(); 00145 00146 // Get prefix manager using the base IRI of the JoystickDrive ontology as default namespace 00147 pm = PREFIX_MANAGER; 00148 00149 // Create empty OWL ontology 00150 ontology = manager.createOntology(IRI.create(IAS_MAP)); 00151 manager.setOntologyFormat(ontology, new RDFXMLOntologyFormat()); 00152 00153 // Import KnowRob ontology 00154 OWLImportsDeclaration oid = factory.getOWLImportsDeclaration(IRI.create(KNOWROB)); 00155 AddImport addImp = new AddImport(ontology,oid); 00156 manager.applyChange(addImp); 00157 00158 00159 00160 // create time point 00161 OWLNamedIndividual time_inst = createTimePointInst(ros.now(), ontology); 00162 00163 00164 00165 // iterate over all objects and create the respective OWL representations 00166 String line; 00167 String objname=""; 00168 00169 while(true) { 00170 00171 line = reader.readLine(); 00172 if(line==null){break;} 00173 if(line.equals("")){continue;} 00174 00175 00176 // new object: line is object name 00177 if(line.matches("[a-zA-Z].*")) { 00178 00179 objname=line; 00180 this.pointsInTrajectories.put(objname, new ArrayList<OWLNamedIndividual>()); 00181 continue; 00182 00183 00184 } else { 00185 00186 String[] qpose = line.split(","); 00187 Point p = new Point(); 00188 p.x = Float.valueOf(qpose[0]); 00189 p.y = Float.valueOf(qpose[1]); 00190 p.z = Float.valueOf(qpose[2]); 00191 00192 Quaternion q = new Quaternion(); 00193 q.x = Float.valueOf(qpose[3]); 00194 q.y = Float.valueOf(qpose[4]); 00195 q.z = Float.valueOf(qpose[5]); 00196 q.w = Float.valueOf(qpose[6]); 00197 00198 double[] matrix = quaternionToMatrix(p,q); 00199 createPointDescription(objname, matrix, time_inst, ontology); 00200 00201 continue; 00202 } 00203 00204 } 00205 00206 for(String obj : pointsInTrajectories.keySet()) { 00207 00208 OWLIndividual owl_traj = createTrajInst(ontology); 00209 00210 OWLNamedIndividual owl_obj = factory.getOWLNamedIndividual("knowrob:"+obj, pm); 00211 OWLObjectProperty prop = factory.getOWLObjectProperty("knowrob:openingTrajectory", pm); 00212 manager.addAxiom(ontology, factory.getOWLObjectPropertyAssertionAxiom(prop, owl_obj, owl_traj)); 00213 00214 00215 prop = factory.getOWLObjectProperty("knowrob:pointOnTrajectory", pm); 00216 00217 for(OWLIndividual point : pointsInTrajectories.get(obj)) { 00218 manager.addAxiom(ontology, factory.getOWLObjectPropertyAssertionAxiom(prop, owl_traj, point)); 00219 } 00220 00221 } 00222 00223 00224 00225 SimpleDateFormat sdf = new SimpleDateFormat("yy-MM-dd_HH-mm-ss-SSS"); 00226 String outfile = "ias_semantic_map_"+sdf.format(new Date())+".owl"; 00227 saveOntologyToFile(ontology, outfile); 00228 00229 00230 } catch (Exception e) { 00231 ontology = null; 00232 e.printStackTrace(); 00233 } 00234 00235 return ontology; 00236 } 00237 00238 00239 00240 00241 00242 00243 protected void createPointDescription(String objname, double[] matrix, OWLNamedIndividual timestamp, OWLOntology ontology) { 00244 00245 // create object instance 00246 OWLNamedIndividual obj_inst = createPointInst(ontology); 00247 00248 // create pose matrix instance 00249 OWLNamedIndividual pose_inst = createPoseInst(matrix, ontology); 00250 00251 // create perception instance 00252 createPerceptionInst(obj_inst, pose_inst, timestamp, ontology); 00253 00254 // remember mapping of ROS object ID and OWL instance (for being able to link to parents) 00255 this.pointsInTrajectories.get(objname).add(obj_inst); 00256 00257 } 00258 00259 00260 00261 protected OWLNamedIndividual createTimePointInst(ros.communication.Time stamp, OWLOntology ontology) { 00262 00263 OWLNamedIndividual time_inst = factory.getOWLNamedIndividual("ias_map:timepoint_"+stamp.secs, pm); 00264 OWLClass time_class = factory.getOWLClass("knowrob:TimePoint", pm); 00265 manager.addAxiom(ontology, factory.getOWLClassAssertionAxiom(time_class, time_inst)); 00266 00267 return time_inst; 00268 } 00269 00270 00271 00272 protected OWLNamedIndividual createPointInst(OWLOntology ontology) { 00273 00274 // create object instance 00275 OWLClass obj_class = factory.getOWLClass("knowrob:Point3D", pm); 00276 OWLNamedIndividual obj_inst = factory.getOWLNamedIndividual( 00277 instForClass("knowrob:Point3D"), pm); 00278 manager.addAxiom(ontology, factory.getOWLClassAssertionAxiom(obj_class, obj_inst)); 00279 00280 return obj_inst; 00281 } 00282 00283 00284 protected OWLNamedIndividual createTrajInst(OWLOntology ontology) { 00285 00286 // create object instance 00287 OWLClass traj_class = factory.getOWLClass("knowrob:ArmTrajectory", pm); 00288 OWLNamedIndividual traj_inst = factory.getOWLNamedIndividual( 00289 instForClass("knowrob:ArmTrajectory"), pm); 00290 manager.addAxiom(ontology, factory.getOWLClassAssertionAxiom(traj_class, traj_inst)); 00291 00292 return traj_inst; 00293 } 00294 00295 00296 00297 protected OWLNamedIndividual createPoseInst(double[] ros_obj, OWLOntology ontology) { 00298 00299 // create pose matrix instance 00300 OWLClass pose_class = factory.getOWLClass("knowrob:RotationMatrix3D", pm); 00301 OWLNamedIndividual pose_inst = factory.getOWLNamedIndividual( 00302 instForClass("ias_map:RotationMatrix3D"), pm); 00303 manager.addAxiom(ontology, factory.getOWLClassAssertionAxiom(pose_class, pose_inst)); 00304 00305 // set pose properties 00306 for(int i=0;i<4;i++) { 00307 for(int j=0;j<4;j++) { 00308 00309 System.out.println("m"+i+j+"="+ros_obj[4*i+j]); 00310 00311 OWLDataProperty prop = factory.getOWLDataProperty("knowrob:m"+i+j, pm); 00312 manager.addAxiom(ontology, factory.getOWLDataPropertyAssertionAxiom(prop, pose_inst, ros_obj[4*i+j])); 00313 } 00314 } 00315 00316 return pose_inst; 00317 } 00318 00319 00320 00321 00322 protected OWLNamedIndividual createPerceptionInst(OWLNamedIndividual obj_inst, OWLNamedIndividual pose_inst, OWLNamedIndividual timestamp, OWLOntology ontology) { 00323 00324 // create perception instance 00325 OWLClass perc_class = factory.getOWLClass("knowrob:TouchPerception", pm); 00326 OWLNamedIndividual perc_inst = factory.getOWLNamedIndividual( 00327 instForClass("knowrob:TouchPerception"), pm); 00328 manager.addAxiom(ontology, factory.getOWLClassAssertionAxiom(perc_class, perc_inst)); 00329 00330 // link to the object instance and the pose instance 00331 OWLObjectProperty objectActedOn = factory.getOWLObjectProperty("knowrob:objectActedOn", pm); 00332 OWLObjectProperty eventOccursAt = factory.getOWLObjectProperty("knowrob:eventOccursAt", pm); 00333 00334 manager.addAxiom(ontology, factory.getOWLObjectPropertyAssertionAxiom(objectActedOn, perc_inst, obj_inst)); 00335 manager.addAxiom(ontology, factory.getOWLObjectPropertyAssertionAxiom(eventOccursAt, perc_inst, pose_inst)); 00336 00337 // set time stamp 00338 OWLObjectProperty startTime = factory.getOWLObjectProperty("knowrob:startTime", pm); 00339 manager.addAxiom(ontology, factory.getOWLObjectPropertyAssertionAxiom(startTime, perc_inst, timestamp)); 00340 00341 return perc_inst; 00342 } 00343 00344 00345 00346 00347 00348 00349 00350 00351 protected String instForClass(String cl) { 00352 cl.replaceAll("knowrob", "ias_map"); 00353 return cl+(inst_counter++); 00354 } 00355 00356 00357 protected static double[] quaternionToMatrix(Point p, Quaternion q) { 00358 00359 double[] m = new double[16]; 00360 00361 double xx = q.x * q.x; 00362 double xy = q.x * q.y; 00363 double xz = q.x * q.z; 00364 double xw = q.x * q.w; 00365 00366 double yy = q.y * q.y; 00367 double yz = q.y * q.z; 00368 double yw = q.y * q.w; 00369 00370 double zz = q.z * q.z; 00371 double zw = q.z * q.w; 00372 00373 m[0] = 1 - 2 * ( yy + zz ); 00374 m[1] = 2 * ( xy - zw ); 00375 m[2] = 2 * ( xz + yw ); 00376 m[3] = p.x; 00377 00378 m[4] = 2 * ( xy + zw ); 00379 m[5] = 1 - 2 * ( xx + zz ); 00380 m[6] = 2 * ( yz - xw ); 00381 m[7] = p.y; 00382 00383 m[8] = 2 * ( xz - yw ); 00384 m[9] = 2 * ( yz + xw ); 00385 m[10] = 1 - 2 * ( xx + yy ); 00386 m[11]=p.z; 00387 00388 m[12]=0; 00389 m[13]=0; 00390 m[14]=0; 00391 m[15]=1; 00392 return m; 00393 } 00394 00395 00396 00397 00400 // 00401 // TODO: copied from RoboEarth -- find a nicer solution, e.g. with a dedicated OWL library package 00402 // 00403 00412 public static boolean saveOntologyToStream(OWLOntology ontology, OutputStream stream, OWLOntologyFormat format) { 00413 00414 boolean ok = false; 00415 00416 if (stream != null) { 00417 00418 try { 00419 00420 // Get hold of the ontology manager 00421 OWLOntologyManager manager = ontology.getOWLOntologyManager(); 00422 00423 // By default ontologies are saved in the format from which they were loaded. 00424 // We can get information about the format of an ontology from its manager 00425 OWLOntologyFormat currFormat = manager.getOntologyFormat(ontology); 00426 00427 if (currFormat.equals(format)) { 00428 00429 // Save a copy of the ontology to the given stream. 00430 manager.saveOntology(ontology, stream); 00431 00432 } else { 00433 00434 // Some ontology formats support prefix names and prefix IRIs. When we save the ontology in 00435 // the new format we will copy the prefixes over so that we have nicely abbreviated IRIs in 00436 // the new ontology document 00437 if (format.isPrefixOWLOntologyFormat() && currFormat.isPrefixOWLOntologyFormat()) { 00438 ((PrefixOWLOntologyFormat)format).copyPrefixesFrom(currFormat.asPrefixOWLOntologyFormat()); 00439 } 00440 manager.saveOntology(ontology, format, stream); 00441 00442 } 00443 00444 ok = true; 00445 00446 } catch (Exception e) { 00447 System.out.println("Could not save ontology: " + e.getMessage()); 00448 } 00449 00450 } 00451 00452 return ok; 00453 } 00454 00455 00462 public static String saveOntologytoString(OWLOntology ontology, OWLOntologyFormat format) { 00463 00464 String s = null; 00465 ByteArrayOutputStream os = new ByteArrayOutputStream(4096); 00466 00467 if (saveOntologyToStream(ontology, os, format)) { 00468 try { 00469 s = new String(os.toByteArray(), "UTF-8"); 00470 } catch (UnsupportedEncodingException e) { 00471 System.out.println("UTF-8 encoding is unsupported: " + e.getMessage()); 00472 } 00473 } 00474 00475 return s; 00476 00477 } 00478 00479 00480 00488 public static boolean saveOntologyToFile(OWLOntology ontology, String file) { 00489 00490 boolean ok = false; 00491 00492 try { 00493 OWLOntologyFormat format = ontology.getOWLOntologyManager().getOntologyFormat(ontology); 00494 ok = saveOntologyToFile(ontology, file, format); 00495 } catch (NullPointerException e) { 00496 System.out.println("Could not save ontology: null pointer argument found\n" + e.getMessage()); 00497 } 00498 00499 return ok; 00500 00501 } 00502 00503 00512 public static boolean saveOntologyToFile(OWLOntology ontology, String file, OWLOntologyFormat format) { 00513 00514 boolean ok = false; 00515 00516 try { 00517 00518 // Build File object 00519 File f = new File(file); 00520 00521 // Get hold of the ontology manager 00522 OWLOntologyManager manager = ontology.getOWLOntologyManager(); 00523 00524 // By default ontologies are saved in the format from which they were loaded. 00525 // We can get information about the format of an ontology from its manager 00526 OWLOntologyFormat currFormat = manager.getOntologyFormat(ontology); 00527 00528 // The Document IRI, where the file should be saved 00529 IRI documentIRI = IRI.create(f.toURI()); 00530 00531 if (currFormat.equals(format)) { 00532 00533 // Save a local copy of the ontology. 00534 manager.saveOntology(ontology, documentIRI); 00535 00536 } else { 00537 00538 // Some ontology formats support prefix names and prefix IRIs. When we save the ontology in 00539 // the new format we will copy the prefixes over so that we have nicely abbreviated IRIs in 00540 // the new ontology document 00541 if (format.isPrefixOWLOntologyFormat() && currFormat.isPrefixOWLOntologyFormat()) { 00542 ((PrefixOWLOntologyFormat)format).copyPrefixesFrom(currFormat.asPrefixOWLOntologyFormat()); 00543 } 00544 manager.saveOntology(ontology, format, documentIRI); 00545 00546 } 00547 00548 ok = true; 00549 00550 } catch (Exception e) { 00551 System.out.println("Could not save ontology: " + e.getMessage()); 00552 } 00553 00554 return ok; 00555 } 00556 00557 00558 00559 // 00560 // 00563 00564 00565 00566 public static void main(String[] args) { 00567 00568 PosesToOWL p2o = new PosesToOWL(); 00569 p2o.buildOWLDescription("poses.txt"); 00570 00571 } 00572 00573 00574 }