yaml2owl.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright (c) 2011, Lars Kunze
00004 # All rights reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions are met:
00008 #
00009 #  * Redistributions of source code must retain the above copyright
00010 #    notice, this list of conditions and the following disclaimer.
00011 #  * Redistributions in binary form must reproduce the above copyright 
00012 #    notice, this list of conditions and the following disclaimer in the 
00013 #    documentation and/or other materials provided with the distribution.
00014 #  * Neither the name of the Intelligent Autonomous Systems Group/
00015 #    Technische Universitaet Muenchen nor the names of its contributors 
00016 #    may be used to endorse or promote products derived from this software 
00017 #    without specific prior written permission.
00018 #
00019 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 
00020 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 
00021 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 
00022 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 
00023 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 
00024 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
00025 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
00026 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
00027 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
00028 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029 # POSSIBILITY OF SUCH DAMAGE.
00030 #
00031 
00032 import string
00033 import time
00034 import sys
00035 import getopt
00036 import yaml
00037 import math
00038 
00039 # global varibles
00040 now = 0.0
00041 vert = False
00042 scale = 1.0
00043 room_height = 4.5
00044 spot_dim = 0.2
00045 id = 0
00046 
00047 ### UTILS ###
00048 
00049 def get_id():
00050     global id
00051     id = id + 1
00052     return id
00053 
00054 def quaternion_to_rotation_mat3d(q, t):
00055     global scale
00056     m = [ [1, 0, 0, 0],
00057           [0, 1, 0, 0],
00058           [0, 0, 1, 0],
00059           [0, 0, 0, 1]]
00060 
00061     x = q['x'] 
00062     y = q['y'] 
00063     z = q['z'] 
00064     w = q['w'] 
00065 
00066     #rotation matrix
00067     #first row
00068     m[0][0] = 1 - 2 * y * y - 2 * z * z
00069     m[0][1] = 2 * x * y - 2 * w * z
00070     m[0][2] = 2 * x * z + 2 * w * y
00071   
00072     # second row 
00073     m[1][0] = 2 * x * y +  2 * w * z
00074     m[1][1] = 1 - 2 * x * x - 2 * z * z
00075     m[1][2] = 2 * y * z - 2 * w * x
00076   
00077     # third row
00078     m[2][0] = 2 * x * z - 2 * w * y
00079     m[2][1] = 2 * y * z + 2 * w * x
00080     m[2][2] = 1 - 2 * x * x - 2 * y * y
00081 
00082     # transposed matrix!
00083     # rotation matrix
00084     # first row
00085     # m[0][0] = 1 - 2 * y * y - 2 * z * z
00086     # m[0][1] = 2 * x * y + 2 * w * z
00087     # m[0][2] = 2 * x * z - 2 * w * y
00088   
00089     # # second row 
00090     # m[1][0] = 2 * x * y - 2 * w * z
00091     # m[1][1] = 1 - 2 * x * x - 2 * z * z
00092     # m[1][2] = 2 * y * z + 2 * w * x
00093   
00094     # # third row
00095     # m[2][0] = 2 * x * z + 2 * w * y
00096     # m[2][1] = 2 * y * z - 2 * w * x
00097     # m[2][2] = 1 - 2 * x * x - 2 * y * y
00098 
00099     # translation
00100     m[0][3] = get_x(t)
00101     m[1][3] = get_y(t)
00102     m[2][3] = get_z(t)
00103     
00104     return m
00105 
00106 
00107 ### YAML ACCESSOR FUNCTIONS ###
00108 
00109 def get_name(name):
00110     n = name.replace('/','-')
00111     if n[0] is '-':
00112         return n[1:]
00113     return n
00114     
00115 def get_room_number(name):
00116     rn = name[name.rfind('-') + 1:]
00117     return rn
00118 
00119 def get_floor_number(name):
00120     n = name[name.rfind('-') + 1:]
00121     fn = n.rstrip(string.ascii_letters)
00122     return fn
00123 
00124 def get_parent(frame):
00125    return frame['frame_id']
00126 
00127 def get_rotation(frame):
00128     return frame['rotation']
00129 
00130 def get_translation(frame):
00131     return frame['translation']
00132 
00133 def get_x(coord):
00134     global scale
00135     return coord['x'] * scale
00136 
00137 def get_y(coord):
00138     global scale
00139     return coord['y'] * scale
00140 
00141 def get_z(coord):
00142     global scale 
00143     return coord['z'] * scale
00144 
00145 def get_types(frame):
00146     return frame['type']
00147 
00148 def get_obj_properties(frame):
00149     if frame.has_key('object-properties'):
00150         return frame['object-properties']
00151     return None
00152 
00153 def get_data_properties(frame):
00154     if frame.has_key('data-properties'):
00155         return frame['data-properties']
00156     return None
00157 
00158 # get actual depth, width, and height
00159 def get_width(r):
00160     global scale;
00161     return r['width'] * scale
00162     
00163 def get_height(r):
00164     global scale
00165     return r['height'] * scale
00166     
00167 def get_depth(r):
00168     global scale
00169     return r['depth'] * scale
00170 
00171 
00172 ### OWL stuff ###    
00173 
00174 def create_header():
00175     print '''<?xml version="1.0"?>
00176 
00177 <!DOCTYPE rdf:RDF [
00178     <!ENTITY local_path "file://@OWL_PATH_PREFIX@/owl/">
00179     <!ENTITY owl "http://www.w3.org/2002/07/owl#" >
00180     <!ENTITY owl2 "http://www.w3.org/2006/12/owl2#" >
00181     <!ENTITY xsd "http://www.w3.org/2001/XMLSchema#" >
00182     <!ENTITY owl2xml "http://www.w3.org/2006/12/owl2-xml#" >
00183     <!ENTITY rdfs "http://www.w3.org/2000/01/rdf-schema#" >
00184     <!ENTITY rdf "http://www.w3.org/1999/02/22-rdf-syntax-ns#" >
00185     <!ENTITY protege "http://protege.stanford.edu/plugins/owl/protege#" >
00186     <!ENTITY knowrob "http://ias.cs.tum.edu/kb/knowrob.owl#" >
00187     <!ENTITY jsk_map "http://www.jsk.t.u-tokyo.ac.jp/jsk_map.owl#" >
00188 ]>
00189 
00190 <rdf:RDF xmlns="http://www.jsk.t.u-tokyo.ac.jp/jsk_map.owl#"
00191      xml:base="http://www.jsk.t.u-tokyo.ac.jp/jsk_map.owl"
00192      xmlns:rdfs="http://www.w3.org/2000/01/rdf-schema#"
00193      xmlns:protege="http://protege.stanford.edu/plugins/owl/protege#"
00194      xmlns:owl2xml="http://www.w3.org/2006/12/owl2-xml#"
00195      xmlns:owl="http://www.w3.org/2002/07/owl#"
00196      xmlns:xsd="http://www.w3.org/2001/XMLSchema#"
00197      xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
00198      xmlns:owl2="http://www.w3.org/2006/12/owl2#"
00199      xmlns:knowrob="http://ias.cs.tum.edu/kb/knowrob.owl#">
00200     <owl:Ontology rdf:about="http://www.jsk.t.u-tokyo.ac.jp/jsk_map.owl#">
00201       <owl:imports rdf:resource="&local_path;knowrob.owl"/>
00202     </owl:Ontology>
00203     
00204  '''
00205     
00206 def create_footer():
00207     print '''
00208 </rdf:RDF>
00209 
00210 <!-- Generated by yaml2owl.py -->
00211 '''
00212 
00213 def create_timepoint(t):
00214     print ''
00215     print '<owl:NamedIndividual rdf:about="&jsk_map;timepoint_{0}">'.format(t)
00216     print '  <rdf:type rdf:resource="&knowrob;TimePoint"/>'
00217     print '</owl:Na1medIndividual>'
00218     print ''
00219 
00220 def create_instance(inst, type):
00221     print ''
00222     print '<owl:NamedIndividual rdf:about="&jsk_map;{0}">'.format(inst)
00223     print '  <rdf:type rdf:resource="http://ias.cs.tum.edu/kb/knowrob.owl#{0}"/>'.format(type)
00224     print '</owl:NamedIndividual>'
00225     print ''
00226 
00227 def create_spot(inst,types,width,height,depth, x, y, z, props=None):
00228     global map_inst
00229     print ''
00230     print '<owl:NamedIndividual rdf:about="&jsk_map;{0}">'.format(inst)
00231     for t in types:
00232         create_type(t)
00233     print '  <knowrob:widthOfObject rdf:datatype="&xsd;float">{0}</knowrob:widthOfObject>'.format(width)
00234     print '  <knowrob:depthOfObject rdf:datatype="&xsd;float">{0}</knowrob:depthOfObject>'.format(depth)
00235     print '  <knowrob:heightOfObject rdf:datatype="&xsd;float">{0}</knowrob:heightOfObject>'.format(height)
00236     print '  <knowrob:describedInMap rdf:resource="&jsk_map;SemanticEnvironmentMap-{0}"/>'.format(map_inst)
00237         
00238     if props is not None:
00239         for p in props:
00240             create_prop(p[0], get_name(p[1]))
00241     print '</owl:NamedIndividual>'
00242     print ''
00243     
00244 def create_object(inst,types,width,height,depth, prop=None, objs=None, x=0.0, y=0.0, z=0.0, data_props=None):
00245     global map_inst
00246     print ''
00247     print '<owl:NamedIndividual rdf:about="&jsk_map;{0}">'.format(inst)
00248     for t in types:
00249         create_type(t)
00250     print '  <knowrob:widthOfObject rdf:datatype="&xsd;float">{0}</knowrob:widthOfObject>'.format(width)
00251     print '  <knowrob:depthOfObject rdf:datatype="&xsd;float">{0}</knowrob:depthOfObject>'.format(depth)
00252     print '  <knowrob:heightOfObject rdf:datatype="&xsd;float">{0}</knowrob:heightOfObject>'.format(height)
00253     print '  <knowrob:describedInMap rdf:resource="&jsk_map;SemanticEnvironmentMap-{0}"/>'.format(map_inst)
00254 
00255     if objs is not None:
00256         if objs.has_key(inst):
00257             create_props(prop, objs[inst])
00258 
00259     if data_props is not None:
00260         for p in data_props:
00261             create_data_prop(p[0], p[1], p[2])
00262             
00263     print '</owl:NamedIndividual>'
00264     print ''
00265     
00266 def create_room(inst,types,width,height,depth, prop=None, objs=None, x=0.0, y=0.0, z=0.0):
00267     global map_inst
00268     print ''
00269     print '<owl:NamedIndividual rdf:about="&jsk_map;{0}">'.format(inst)
00270     for t in types:
00271         create_type(t)
00272     print '  <knowrob:widthOfObject rdf:datatype="&xsd;float">{0}</knowrob:widthOfObject>'.format(width)
00273     print '  <knowrob:depthOfObject rdf:datatype="&xsd;float">{0}</knowrob:depthOfObject>'.format(depth)
00274     print '  <knowrob:heightOfObject rdf:datatype="&xsd;float">{0}</knowrob:heightOfObject>'.format(height)
00275     print '  <knowrob:describedInMap rdf:resource="&jsk_map;SemanticEnvironmentMap-{0}"/>'.format(map_inst)
00276 
00277     print '  <knowrob:roomNumber rdf:datatype="&xsd;string">{0}</knowrob:roomNumber>'.format(get_room_number(inst))
00278         
00279     if objs is not None:
00280         if objs.has_key(inst):
00281             create_props(prop, objs[inst])
00282     print '</owl:NamedIndividual>'
00283     print ''
00284 
00285 def create_level(inst,types,width,height,depth, prop=None, objs=None, x=0.0, y=0.0, z=0.0):
00286     global map_inst
00287     print ''
00288     print '<owl:NamedIndividual rdf:about="&jsk_map;{0}">'.format(inst)
00289     for t in types:
00290         create_type(t)
00291     print '  <knowrob:widthOfObject rdf:datatype="&xsd;float">{0}</knowrob:widthOfObject>'.format(width)
00292     print '  <knowrob:depthOfObject rdf:datatype="&xsd;float">{0}</knowrob:depthOfObject>'.format(depth)
00293     print '  <knowrob:heightOfObject rdf:datatype="&xsd;float">{0}</knowrob:heightOfObject>'.format(height)
00294     print '  <knowrob:describedInMap rdf:resource="&jsk_map;SemanticEnvironmentMap-{0}"/>'.format(map_inst)
00295 
00296     print '  <knowrob:floorNumber rdf:datatype="&xsd;string">{0}</knowrob:floorNumber>'.format(get_floor_number(inst))
00297         
00298     if objs is not None:
00299         if objs.has_key(inst):
00300             create_props(prop, objs[inst])
00301     print '</owl:NamedIndividual>'
00302     print ''
00303 
00304     
00305 def create_type(type):
00306     print '  <rdf:type rdf:resource="&knowrob;{0}"/>'.format(type)
00307 
00308 def create_bldg(inst,types,width,height,depth, prop=None, objs=None, x=0.0, y=0.0, z=0.0):
00309     global map_inst
00310     print '<owl:NamedIndividual rdf:about="&jsk_map;{0}">'.format(inst)
00311     for t in types:
00312         create_type(t)
00313     print '  <knowrob:widthOfObject rdf:datatype="&xsd;float">{0}</knowrob:widthOfObject>'.format(width)
00314     print '  <knowrob:depthOfObject rdf:datatype="&xsd;float">{0}</knowrob:depthOfObject>'.format(depth)
00315     print '  <knowrob:heightOfObject rdf:datatype="&xsd;float">{0}</knowrob:heightOfObject>'.format(height)
00316     print '  <knowrob:describedInMap rdf:resource="&jsk_map;SemanticEnvironmentMap-{0}"/>'.format(map_inst)
00317     if objs is not None:
00318         if objs.has_key(inst):
00319             create_props(prop, objs[inst])
00320     print '</owl:NamedIndividual>'    
00321     
00322 def create_props(prop, objs):
00323     for o in objs:
00324         create_prop(prop,o)
00325     
00326 def create_prop(prop, obj):
00327     print '  <knowrob:{0} rdf:resource="&jsk_map;{1}"/>'.format(prop,obj)
00328 
00329 def create_data_prop(prop, type, val):
00330     print '  <knowrob:{0} rdf:datatype="&xsd;{1}">{2}</knowrob:{0}>'.format(prop,type,val)
00331     
00332 def create_perception_event(obj,mat3d_name,time=0):
00333     print   ''
00334     print   '<owl:NamedIndividual rdf:about="&jsk_map;SemanticMapPerception-{0}">'.format(get_id())
00335     print   '  <rdf:type rdf:resource="&knowrob;SemanticMapPerception"/>'
00336     print   '  <knowrob:objectActedOn rdf:resource="&jsk_map;{0}"/>'.format(obj)
00337     print   '  <knowrob:eventOccursAt rdf:resource="&jsk_map;{0}"/>'.format(mat3d_name)
00338     print   '  <knowrob:startTime rdf:resource="&jsk_map;timepoint_{0}"/>'.format(time)
00339     print   '</owl:NamedIndividual>'
00340     print   ''
00341     
00342 
00343 def create_rot_mat3d(m):
00344     name = 'RotationMatrix3D-{0}'.format(get_id())
00345     print ''
00346     print '<owl:NamedIndividual rdf:about="&jsk_map;{0}">'.format(name)
00347     print '  <rdf:type rdf:resource="&knowrob;RotationMatrix3D"/>'
00348     print '  <knowrob:m00 rdf:datatype="&xsd;float">{0}</knowrob:m00>'.format(m[0][0])
00349     print '  <knowrob:m01 rdf:datatype="&xsd;float">{0}</knowrob:m01>'.format(m[0][1])
00350     print '  <knowrob:m02 rdf:datatype="&xsd;float">{0}</knowrob:m02>'.format(m[0][2])
00351     print '  <knowrob:m03 rdf:datatype="&xsd;float">{0}</knowrob:m03>'.format(m[0][3])
00352     print '  <knowrob:m10 rdf:datatype="&xsd;float">{0}</knowrob:m10>'.format(m[1][0])
00353     print '  <knowrob:m11 rdf:datatype="&xsd;float">{0}</knowrob:m11>'.format(m[1][1])
00354     print '  <knowrob:m12 rdf:datatype="&xsd;float">{0}</knowrob:m12>'.format(m[1][2])
00355     print '  <knowrob:m13 rdf:datatype="&xsd;float">{0}</knowrob:m13>'.format(m[1][3])
00356     print '  <knowrob:m20 rdf:datatype="&xsd;float">{0}</knowrob:m20>'.format(m[2][0])
00357     print '  <knowrob:m21 rdf:datatype="&xsd;float">{0}</knowrob:m21>'.format(m[2][1])
00358     print '  <knowrob:m22 rdf:datatype="&xsd;float">{0}</knowrob:m22>'.format(m[2][2])
00359     print '  <knowrob:m23 rdf:datatype="&xsd;float">{0}</knowrob:m23>'.format(m[2][3])
00360     print '  <knowrob:m30 rdf:datatype="&xsd;float">{0}</knowrob:m30>'.format(m[3][0])
00361     print '  <knowrob:m31 rdf:datatype="&xsd;float">{0}</knowrob:m31>'.format(m[3][1])
00362     print '  <knowrob:m32 rdf:datatype="&xsd;float">{0}</knowrob:m32>'.format(m[3][2])
00363     print '  <knowrob:m33 rdf:datatype="&xsd;float">{0}</knowrob:m33>'.format(m[3][3])
00364     print '</owl:NamedIndividual>'
00365     print ''
00366     return name
00367 
00368 ### CREATING OWL FROM YAML ###
00369 
00370 def create_levels(map, has_rooms, now):
00371     global room_height
00372     
00373     # read floors
00374     # create floors with rooms 
00375     has_floors = dict()
00376     floors = map.get('floor')
00377     if floors is not None:
00378         for f in floors:
00379 
00380             name = get_name(f)
00381             parent = get_name(get_parent(floors[f]))
00382             
00383             # remember the parent (building) of the floor, in order to add the hasLevels property to the building
00384             if not has_floors.has_key(parent):
00385                 has_floors[parent] = [name] 
00386             else:
00387                 has_floors[parent] = has_floors[parent] + [name]
00388                 
00389 
00390             q = get_rotation(floors[f])
00391             trans = get_translation(floors[f])
00392             trans_cpy = trans.copy()
00393 
00394             if vert:
00395                 trans_cpy['x'] = get_width(floors[f])/2 #trans['z']
00396                 trans_cpy['z'] = (float(get_floor_number(name))-1.0) * room_height  + trans['z']             
00397                 
00398             mat3d = quaternion_to_rotation_mat3d(q,trans_cpy)
00399 
00400             create_level(name,
00401                          ['LevelOfAConstruction'],
00402                          get_depth(floors[f]), get_height(floors[f]), get_width(floors[f]),
00403                          'hasRooms', has_rooms,
00404                          get_x(trans), get_y(trans), get_z(trans))
00405             
00406             mat_inst = create_rot_mat3d(mat3d)
00407                 
00408             create_perception_event(name, mat_inst, now)
00409             
00410     return has_floors
00411 
00412 
00413 def create_rooms(map, now):
00414     global room_height
00415     # read rooms
00416     has_rooms = dict()
00417     rooms = map.get('room')
00418     if rooms is not None:
00419         for r in rooms:
00420 
00421             name = get_name(r)
00422             parent = get_name(get_parent(rooms[r]))
00423             
00424                 # remember the parent (floor) of the room, in order to add the hasRooms property to the floor
00425             if not has_rooms.has_key(parent):
00426                 has_rooms[parent] = [name] 
00427             else:
00428                 has_rooms[parent] = has_rooms[parent] + [name]
00429                 
00430             q = get_rotation(rooms[r])
00431             trans = get_translation(rooms[r])
00432             trans_cpy = trans.copy()
00433                 
00434             if vert:
00435                 trans_cpy['x'] = trans['x'] - get_translation((map.get('floor'))[get_parent(rooms[r])])['x'] +  get_width( (map.get('floor'))[get_parent(rooms[r])])/2
00436                 trans_cpy['z'] = (float(get_floor_number(get_name(get_parent(rooms[r])))) - 1.0) * room_height + trans['z'] #['x']
00437 
00438             mat3d = quaternion_to_rotation_mat3d(q,trans_cpy)
00439 
00440             # switched width and height !!!!
00441             create_room(name,
00442                         get_types(rooms[r]),  #['RoomInAConstruction'],
00443                         get_depth(rooms[r]), get_height(rooms[r]), get_width(rooms[r]),
00444                         None, None,  get_x(trans), get_y(trans), get_z(trans))
00445 
00446             mat_inst = create_rot_mat3d(mat3d)
00447 
00448             create_perception_event(name, mat_inst, now)
00449 
00450     return has_rooms
00451 
00452 
00453 def create_objs(map, now):
00454     has_objs = dict()
00455     objs = map.get('object')
00456     if objs is not None:
00457         for o in objs:
00458             
00459             name =   get_name(o)
00460             parent = get_name(get_parent(objs[o]))
00461 
00462                         
00463             # remember the parent (room) of the obj, in order to add the hasObjs property to the room
00464             if not has_objs.has_key(parent):
00465                 has_objs[parent] = [name] 
00466             else:
00467                 has_objs[parent] = has_objs[parent] + [name]
00468                 
00469             q = get_rotation(objs[o])
00470             trans = get_translation(objs[o])
00471             trans_cpy = trans.copy()
00472 
00473             if vert:
00474                 if map.get('room').has_key(get_parent(objs[o])):
00475                     trans_cpy['x'] = trans['x'] -  get_translation( (map.get('floor'))[ get_parent((map.get('room'))[get_parent(objs[o])]) ])['x'] + get_width((map.get('floor'))[ get_parent((map.get('room'))[get_parent(objs[o])])])/2
00476                     trans_cpy['z'] = (float(get_floor_number(get_name(get_parent( (map.get('room'))[get_parent(objs[o])]))))-1.0) * room_height + trans['z'] # ['x']
00477                 elif map.get('floor').has_key(get_parent(objs[o])):
00478                     trans_cpy['x'] = trans['x'] -  get_translation( (map.get('floor'))[ get_parent(objs[o])])['x'] +  get_width( (map.get('floor'))[get_parent(objs[o])])/2
00479                     trans_cpy['z'] = (float(get_floor_number(get_name(get_parent((objs[o]))))) - 1.0) * room_height + trans['z'] # ['x']
00480                 else: # all objects need parent!!!
00481                     break
00482                     
00483             mat3d = quaternion_to_rotation_mat3d(q,trans_cpy)
00484 
00485             data_props = get_data_properties(objs[o])
00486 
00487             create_object(name,get_types(objs[o]),get_depth(objs[o]),get_height(objs[o]),get_width(objs[o]), None, None,  get_x(trans), get_y(trans), get_z(trans), data_props)
00488 
00489             mat_inst = create_rot_mat3d(mat3d)
00490             
00491             create_perception_event(name, mat_inst, now)
00492 
00493 def create_spots(map, now):
00494     global spot_dim
00495     spots = map.get('spots')
00496     if spots is not None:
00497         for s in spots:
00498             
00499             name =   get_name(s)
00500                         
00501             q = get_rotation(spots[s])
00502             trans = get_translation(spots[s])
00503             trans_cpy = trans.copy()
00504 
00505             if vert:
00506                 if map.get('room').has_key(get_parent(spots[s])):
00507                     trans_cpy['x'] = trans['x'] -  get_translation( (map.get('floor'))[ get_parent((map.get('room'))[get_parent(spots[s])]) ])['x'] + get_width((map.get('floor'))[ get_parent((map.get('room'))[get_parent(spots[s])])])/2
00508                     trans_cpy['z'] = (float(get_floor_number(get_name(get_parent( (map.get('room'))[get_parent(spots[s])]))))-1.0) * room_height + trans['z'] # ['x']
00509                 elif map.get('floor').has_key(get_parent(spots[s])):
00510                     trans_cpy['x'] = trans['x'] -  get_translation( (map.get('floor'))[ get_parent(spots[s])])['x'] +  get_width( (map.get('floor'))[get_parent(spots[s])])/2
00511                     trans_cpy['z'] = (float(get_floor_number(get_name(get_parent((spots[s]))))) - 1.0) * room_height + trans['z'] # ['x']
00512                 else: # all objects need parent!!!
00513                     break
00514                 
00515             mat3d = quaternion_to_rotation_mat3d(q,trans_cpy)
00516 
00517             props = get_obj_properties(spots[s])
00518             
00519             create_spot(name,['Place'],spot_dim,spot_dim/2,spot_dim, get_x(trans), get_y(trans), get_z(trans), props)
00520 
00521             mat_inst = create_rot_mat3d(mat3d)
00522             
00523             create_perception_event(name, mat_inst, now)
00524             
00525 
00526 def create_map(map, now):
00527     global map_inst
00528     # read building, because building name become map name
00529     buildings = map.get('building')
00530     if buildings is not None:
00531         b = buildings.keys()
00532         map_inst = get_name(b[0])
00533         create_instance('SemanticEnvironmentMap-' + map_inst,
00534                         'SemanticEnvironmentMap')
00535 
00536 def create_building(map, now, has_floors):    
00537     # read building
00538     buildings = map.get('building')
00539     if buildings is not None:
00540         b = buildings.keys()
00541         name  = get_name(b[0])
00542         q = get_rotation(buildings[b[0]])
00543         trans = get_translation(buildings[b[0]])
00544         trans_cpy = trans.copy()
00545         
00546         if vert:
00547             trans_cpy['x'] = get_width(buildings[b[0]])/2 #trans['z'] +
00548             trans_cpy['z'] = trans['x'] # maximoiun level numnber * room_height   
00549                 
00550         mat3d = quaternion_to_rotation_mat3d(q,trans_cpy)
00551             
00552         create_bldg(name,
00553                     get_types(buildings[b[0]]), #['Building'],
00554                     get_depth(buildings[b[0]]),
00555                     get_height(buildings[b[0]]),
00556                     get_width(buildings[b[0]]),
00557                     'hasLevels', has_floors,
00558                     get_x(trans), get_y(trans), get_z(trans))
00559 
00560         mat_inst = create_rot_mat3d(mat3d)
00561             
00562         create_perception_event(name, mat_inst, now)
00563 
00564         
00565         
00566     
00567 #______________________________________________________________________________
00568 # main  
00569 
00570 class Usage(Exception):
00571     def __init__(self, msg):
00572         self.msg = msg
00573 
00574 def help_msg():
00575     return """
00576   Usage: yaml2owl.py [-h] <map>
00577 
00578     map               name of the yaml file 
00579 
00580     -h, --help  for seeing this msg
00581     -v, --vert  for creating the map vertically
00582     -s, --scale for scaling the map
00583 
00584 """
00585 
00586 def main(argv=None):
00587     global map_inst, vert, scale, now
00588     if argv is None:
00589         argv = sys.argv
00590     try:
00591         try:
00592             opts, args = getopt.getopt(argv[1:], "svh", ["scale", "vert", "help"])
00593         except getopt.error, msg:
00594             raise Usage(msg)
00595 
00596         if ('-h','') in opts or ('--help', '') in opts: #len(args) != 2 or
00597             raise Usage(help_msg())
00598 
00599         if ('-v','') in opts or ('--vert', '') in opts:
00600             vert = True
00601 
00602         if ('-s','') in opts or ('--scale', '') in opts:
00603             scale = 0.1
00604 
00605         # read yaml file
00606         stream = file(args[0],'r')
00607         map = yaml.load(stream)
00608 
00609         now = int(time.time())
00610 
00611         create_header()
00612 
00613         create_map(map,now)
00614 
00615         has_rooms = create_rooms(map, now)
00616 
00617         has_floors = create_levels(map, has_rooms, now)
00618 
00619         create_objs(map, now)
00620 
00621         create_building(map, now, has_floors)
00622 
00623         create_spots(map,now)
00624     
00625         create_footer()
00626 
00627     except Usage, err:
00628         print >>sys.stderr, err.msg
00629         print >>sys.stderr, "for help use --help"
00630         return 2
00631     
00632 if __name__ == "__main__":
00633     sys.exit(main())
00634 
00635 # deprecated 
00636 #
00637 # def quaternion_to_rotation_mat3d(q, t, r):
00638 #     global scale
00639 #     m = [ [1, 0, 0, 0],
00640 #           [0, 1, 0, 0],
00641 #           [0, 0, 1, 0],
00642 #           [0, 0, 0, 1]]
00643 
00644 #     x = q['x'] 
00645 #     y = q['y'] 
00646 #     z = q['z'] 
00647 #     w = q['w'] 
00648 
00649 #     # rotation matrix
00650 #     # first row
00651 #     m[0][0] = 1 - 2 * y * y - 2 * z * z
00652 #     m[0][1] = 2 * x * y + 2 * w * z
00653 #     m[0][2] = 2 * x * z - 2 * w * y
00654   
00655 #     # # # second row 
00656 #     m[1][0] = 2 * x * y - 2 * w * z
00657 #     m[1][1] = 1 - 2 * x * x - 2 * z * z
00658 #     m[1][2] = 2 * y * z + 2 * w * x
00659   
00660 #     # # # third row
00661 #     m[2][0] = 2 * x * z + 2 * w * y
00662 #     m[2][1] = 2 * y * z - 2 * w * x
00663 #     m[2][2] = 1 - 2 * x * x - 2 * y * y
00664 
00665 #     # # fourth row 
00666 #     # m[3][0] = 0
00667 #     # m[3][1] = 0
00668 #     # m[3][2] = 0
00669 
00670 #     # region should always be None now!
00671 #     if r is None:
00672 #         m[0][3] = get_x(t)
00673 #         m[1][3] = get_y(t)
00674 #         m[2][3] = get_z(t)
00675 #         m[3][3] = 1
00676 #         return m
00677 
00678 #     # calculate the center of room (2D only)
00679 #     xs = [xval[0] for xval in r]
00680 #     ys = [yval[1] for yval in r]
00681     
00682 #     cent_x = (math.fsum(xs) / float(len(xs))) * scale 
00683 #     cent_y = (math.fsum(ys) / float(len(ys))) * scale
00684 #     cent_z = 0
00685 
00686 #     # rotate the center point
00687 #     #rot_x = m[0][0] * cent_x + m[0][1] * cent_y + m[0][2] * cent_z 
00688 #     #rot_y = m[1][0] * cent_x + m[1][1] * cent_y + m[1][2] * cent_z
00689 #     #rot_z = m[2][0] * cent_x + m[2][1] * cent_y + m[2][2] * cent_z
00690 
00691 #     # now set translation of obj 
00692 #     m[0][3] = get_x(t) + cent_x#+ rot_x 
00693 #     m[1][3] = get_y(t) + cent_y#+ rot_y 
00694 #     m[2][3] = get_z(t) + cent_z#+ rot_z
00695 #     m[3][3] = 1
00696 
00697 #     # print "q ", q
00698 #     # print "x ", x
00699 #     # print "y ", y
00700 #     # print "z ", z
00701 #     # print "w ", w
00702 #     # print "t ", t
00703 #     # print "r ", r
00704 #     # # print "trans x/y ", get_x(t), " ", get_y(t) 
00705 #     # # print "cent x/y ", cent_x, " ", cent_y  
00706 #     # # print "rot x/y/z ", rot_x, " ", rot_y, " ",  rot_z
00707 #     # print "m  x/y ", m[0][3] , " ", m[1][3]
00708 #     # print m
00709     
00710 #     return m
00711 
00712  
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


jsk_maps
Author(s): Manabu Saito, Haseru Chen
autogenerated on Sat Mar 23 2013 15:46:46