semantic_framer.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # semantic_framer.py
00003 
00004 import roslib; roslib.load_manifest('semantic_framer')
00005 import rospy
00006 import os
00007 import sys
00008 import yaml
00009 from roboframenet_msgs.msg import *
00010 from roboframenet_msgs.srv import *
00011 from stanford_parser_msgs.msg import Parse
00012 from stanford_parser_msgs import unsquash_tree
00013 
00014 
00015 
00016 
00017 ###############################################################################
00018 ### Internal Classes
00019 
00020 class _Verb():
00021     def __init__(self, name, index):
00022         self.name = name
00023         self.index = index
00024         self.is_negated = False
00025 
00026     def negate(self):
00027         self.is_negated = not self.is_negated
00028 
00029     def __repr__(self):
00030         return ("<_Verb '" + self.name + "' (index " + str(self.index) + "): " +
00031                 ("not " if (not self.is_negated) else "") + "negated>")
00032 
00033 
00034 
00035 class _LexicalUnit(object):
00036     def __init__(self, name, verb):
00037         self.frame_name = name # string
00038         self.verb = verb # string
00039         self.frame_element_grammatical_relations = [] #listof(_FrameElementGrammaticalRelation)
00040 
00041     # Returns listof(_LexicalUnit).
00042     @staticmethod
00043     def import_yaml(yaml):
00044         lus = []
00045         try:
00046             # yaml is either a single lu entry or a listof(lu entry)
00047             for yaml in listify(yaml):
00048                 # verb is either a single verb or a listof(verb)
00049                 for verb in listify(yaml['verb']):
00050                     lu = _LexicalUnit(yaml['frame_name'], verb)
00051                     frame = get_EmptySemanticFrame(lu.frame_name)
00052                     if 'frame_element_grammatical_relations' in yaml:
00053                         for gr in yaml['frame_element_grammatical_relations']:
00054                             # Check coreness with frame (assume False if not found,
00055                             #   since we won't be mapping it.)
00056                             is_core = False
00057                             for fe in frame.frame_elements:
00058                                 if fe.name == gr['name']:
00059                                     is_core = fe.is_core
00060                                     break
00061                             lu.frame_element_grammatical_relations.append(
00062                                 _FrameElementGrammaticalRelation(gr['name'],
00063                                                                  gr['relation'],
00064                                                                  is_core))
00065                     lus.append(lu)
00066         except:
00067             rospy.logerr("Error converting yaml to _LexicalUnit: " +
00068                          str(sys.exc_info()))
00069         else:
00070             return lus
00071 
00072     def __str__(self):
00073         return "<_LexicalUnit '" + self.verb + "' -> '" + self.frame_name + "'>"
00074 
00075 
00076 
00077 class _FrameElementGrammaticalRelation:
00078     def __init__(self, name, relation, is_core):
00079         self.name = name # string
00080         self.relation = relation # string
00081         self.is_core = is_core
00082 
00083 
00084 
00085 
00086 
00087 ###############################################################################
00088 ### Helpers (External)
00089 
00090 def get_EmptySemanticFrame(frame_name):
00091     rospy.wait_for_service('get_empty_frame')
00092     try:
00093         srv = rospy.ServiceProxy('get_empty_frame', GetEmptyFrame)
00094         frame = srv(frame_name).frame
00095     except rospy.ServiceException, e:
00096         print "Service call failed: %s"%e
00097         return False
00098     return frame
00099 
00100 
00101 
00102 
00103 ###############################################################################
00104 ### Helpers (Internal)
00105 
00106 def listify(x):
00107     return x if isinstance(x, list) else [x]
00108 
00109 # Returns dict(listof(_LexicalUnit)); Dictionary keyed by index of verb.
00110 def get_empty_lexical_units(msg):
00111     # Force all words in the sentence to be lower case.  This makes
00112     #   capitalization a non-issue for, eg, verbs at the start of a
00113     #   sentence, or for any other sort of comparison in general.
00114     for i in range(len(msg.words)):
00115         msg.words[i] = msg.words[i].lower()
00116     # Unsquash the parse tree and find the verb
00117     parse_tree = unsquash_tree(msg)
00118     # Ignore negated verbs.  (We don't want the robot to start doing something
00119     #   you said not to do.  eg, "Don't break my dishes!")
00120     verbs = filter(lambda verb: not verb.is_negated,
00121                    find_verbs_in_parse(parse_tree,
00122                                        msg.dependencies,
00123                                        msg.words))
00124     # Get verb-relevant lexical units
00125     rospy.loginfo("semantic_framer: Retrieving empty lexical units for " +
00126                   str(len(verbs)) + " verb(s): '" +
00127                   "', '".join(map(lambda v: v.name, verbs)) + "'.")
00128     all_empty_lexical_units = dict()
00129     for verb in verbs:
00130         all_empty_lexical_units[verb.index] = get_lexical_units(verb.name)
00131     num_elus = sum([len(elus)
00132                     for verb_index, elus
00133                     in all_empty_lexical_units.items()])
00134     rospy.loginfo("semantic_framer: Retrieved " + str(num_elus) +
00135                   " empty lexical unit(s):\n" +
00136                   "verb\t->\tsemantic frame\n" +
00137                   "---------------------------------\n" +
00138                   '\n'.join(map(lambda elu: (elu.verb +
00139                                              '\t->\t' +
00140                                              elu.frame_name),
00141                                 sum([elus
00142                                      for verb_index, elus
00143                                      in all_empty_lexical_units.items()],
00144                                     []))) +
00145                   '\n')
00146     return all_empty_lexical_units, num_elus
00147 
00148 
00149 
00150 def find_verbs_in_parse(tree, dependencies, words):
00151     def find_all_verbs(tree):
00152         # Pull out all verbs:
00153         # VB - Verb, base form
00154         # VBD - Verb, past tense
00155         # VBG - Verb, gerund or present participle
00156         # VBN - Verb, past participle
00157         # VBP - Verb, non-3rd person singular present
00158         # VBZ - Verb, 3rd person singular present
00159         verbs = []
00160         if (tree.word and
00161             tree.tag in ["VB", "VBD", "VBG", "VBN", "VBP", "VBZ"]):
00162             verbs.append(_Verb(tree.word, tree.word_index))
00163         # Get verbs from children
00164         for child in tree.children:
00165             verbs.extend(find_all_verbs(child))
00166         return verbs
00167     # Heuristic (in order):
00168     # Find all verbs
00169     verbs = find_all_verbs(tree)
00170     # Mark nothing to be removed originally
00171     will_remove = map(lambda x: False, range(len(verbs)))
00172     for dep in dependencies:
00173         for i in range(len(verbs)):
00174             if (# Take both verbs from: conj_and, conj_or.  (This currently
00175                 #   has no effect; we just interpret everything as "or".)
00176                 False or
00177                 # Remove all verbs that are the second argument of: advcl, aux,
00178                 #   auxpass, csubj, csubjpass, expl, parataxis
00179                 (dep.relation in ["advcl", "aux", "auxpass", "csubj",
00180                                   "csubjpass", "expl", "parataxis"] and
00181                  verbs[i].index == dep.dependent_index) or
00182                 # Remove all verbs that are an argument of: mark
00183                 (dep.relation == "mark" and
00184                  (verbs[i].index == dep.governor_index or
00185                   verbs[i].index == dep.dependent_index))):
00186                 will_remove[i] = True
00187             # Look for neg where verb is the second argument to determine negations.
00188             elif dep.relation == "neg":
00189                 if verbs[i].index == dep.dependent_index:
00190                     verbs[i].negate()
00191     # (End)
00192     # Remove marked verb elements
00193     iterator = range(len(verbs))
00194     iterator.reverse()
00195     for i in iterator:
00196         if will_remove[i]:
00197             verbs.pop(i)
00198     return verbs
00199 
00200 
00201 
00202 def fill_empty_lexical_units(all_empty_lexical_units, msg):
00203     # Try to fill out the given lexical units
00204     all_filled_lexical_units = dict(map(lambda verb_index: [verb_index,[]],
00205                                         all_empty_lexical_units.keys()))
00206     for verb_index, empty_lexical_units in all_empty_lexical_units.items():
00207         for elu in empty_lexical_units:
00208             flu = fill_empty_lexical_unit(elu, verb_index, msg.dependencies, msg.words)
00209             if flu:
00210                 all_filled_lexical_units[verb_index].append(flu)
00211     # See how many we filled
00212     num_flus = sum([len(flus)
00213                     for verb_index, flus
00214                     in all_filled_lexical_units.items()])
00215     return all_filled_lexical_units, num_flus
00216 
00217 
00218 # Try filling out the lexical unit.  Return a FilledLexicalUnit, or False if not possible.
00219 def fill_empty_lexical_unit(elu, verb_index, dependencies, words):
00220     flu = FilledLexicalUnit()
00221     flu.frame_name = elu.frame_name
00222     flu.verb = elu.verb
00223     flu.frame_elements = []
00224     # - Get relations from elu and dependencies from parse, and determine
00225     #     corresponding word for each elu relation.
00226     for relation in elu.frame_element_grammatical_relations:
00227         matches = match_dependencies([verb_index],
00228                                      dependencies,
00229                                      str.split(relation.relation, '/'))
00230         if matches:
00231             fe = FilledFrameElement()
00232             fe.name = relation.name
00233             fe.argument = words[matches[0]]
00234             flu.frame_elements.append(fe)
00235         elif relation.is_core:
00236             return False # We needed that relation, and we didn't have it.
00237     return flu
00238 
00239 
00240 # verb_indices is listof(int)
00241 # dependencies is listof(Dependency)
00242 # relations_list is, eg, [num,pobj,advmod] (num of the pobj of the advmod of the verb)
00243 # returns listof(int), the indices which match
00244 def match_dependencies(verb_indices, dependencies, relations_list):
00245     def match_dependencies_recursive(word_indices, dependencies, relations_list):
00246         # Either we're at the end or we're out of things to search for.
00247         if relations_list == [] or not word_indices: return word_indices
00248         relation = relations_list.pop()
00249         matching_dependencies = filter(lambda dep:
00250                                            (dep.relation == relation and
00251                                             dep.governor_index in word_indices),
00252                                        dependencies)
00253         matching_indices = map(lambda dep: dep.dependent_index, matching_dependencies)
00254         return match_dependencies_recursive(matching_indices, dependencies, relations_list)
00255     # Clone relations list so we don't modify it.
00256     r = []
00257     r.extend(relations_list)
00258     return match_dependencies_recursive(verb_indices, dependencies, r)
00259 
00260 
00261 def publish_filled_lexical_units(pub, filled_lexical_units):
00262     flus = FilledLexicalUnitList()
00263     flus.lexical_units = []
00264     for verb_index, filled_lexical_units in filled_lexical_units.items():
00265         flus.lexical_units.extend(filled_lexical_units)
00266     pub.publish(flus)
00267     return
00268 
00269 
00270 
00271 ###############################################################################
00272 ### Lexical unit storage
00273 
00274 lexical_units = {}   # Index: string (verb) ; Element: listof(_LexicalUnit) (list of lexical units associated with a verb)
00275 
00276 # verb is a string
00277 # Retrives lexical unit from the database.
00278 # Returns a listof(_LexicalUnit).  (Empty list if not found.)
00279 def get_lexical_units(verb):
00280     global lexical_units
00281     if verb in lexical_units:
00282         return lexical_units[verb]
00283     else:
00284         rospy.logwarn("get_lexical_units: verb '" + verb +
00285                       "' not found.  (This may be normal.  Or not.)")
00286         return []
00287 
00288 
00289 # Stores semantic frame in the database.
00290 # Returns True on success and False on failure.
00291 def store_lexical_unit(lu):
00292     global lexical_units
00293     if not isinstance(lu, _LexicalUnit):
00294         rospy.logerr("store_lexical_unit: Given object (" + str(lu) +
00295                      ") is not a _LexicalUnit object!  Ignoring request.")
00296         return False
00297     else:
00298         if lu.verb not in lexical_units:
00299             lexical_units[lu.verb] = []
00300         lexical_units[lu.verb].append(lu)
00301         rospy.loginfo("Added new lexical unit " + str(lu) + ".")
00302         return True
00303 
00304 
00305 # Loads lexical unit and stores it in the database.
00306 # Returns True on success and False on failure.
00307 def load_lexical_unit_yaml(filename):
00308     global lexical_units
00309     try:
00310         lu_yaml = yaml.load(open(filename, 'r'))
00311     except:
00312         rospy.logerr("Error loading file '%s': %s" % (str(filename), str(sys.exc_info())))
00313         return False
00314     else:
00315         # Load multiple lexical units as a list in a single file, too.
00316         # result is False if one or more calls to store_lexical_unit returns False.
00317         rospy.loginfo("Loading lexical units from: " + filename)
00318         result = not sum(map(lambda lu: not store_lexical_unit(lu),
00319                              _LexicalUnit.import_yaml(lu_yaml)))
00320         if not result:
00321             rospy.logerr("Could not add lexical unit(s) from '" + filename + "'!")
00322         return result
00323 
00324 
00325 
00326 
00327 
00328 ###############################################################################
00329 ### ROS Callbacks
00330 
00331 def cb_AddLexicalUnit(req):
00332     response = AddLexicalUnitResponse()
00333     response.success = load_lexical_unit_yaml(req.absolute_file_path)
00334     return response
00335 
00336 
00337 def cb_parse(msg, pub):
00338     elus, num_elus = get_empty_lexical_units(msg)
00339     if num_elus == 0:
00340         rospy.logwarn("cb_parse: Did not receive any lexical units!  Aborting.")
00341         return
00342     flus, num_flus = fill_empty_lexical_units(elus, msg)
00343     if num_flus == 0:
00344         rospy.logwarn("cb_parse: Could not fill any lexical units!  Aborting.")
00345         return
00346     publish_filled_lexical_units(pub, flus)
00347 
00348 
00349 
00350 
00351 
00352 ###############################################################################
00353 ### Main
00354 
00355 def main():
00356     rospy.init_node('semantic_framer')
00357 
00358     lu_relpath = '../lu' # relative to this binary
00359     lu_filenames    = filter(lambda fn: fn[-5:] == '.yaml', os.listdir(lu_relpath))
00360     rospy.loginfo("semantic_framer: Loading lexical units...")
00361     for lu_filename in lu_filenames:
00362         load_lexical_unit_yaml(os.path.join(lu_relpath, lu_filename))
00363     rospy.loginfo("semantic_framer: Done loading lexical units.")
00364 
00365     rospy.Service('add_lexical_unit',       AddLexicalUnit,       cb_AddLexicalUnit)
00366     pub = rospy.Publisher('filled_lexical_units', FilledLexicalUnitList)
00367     rospy.Subscriber('parse', Parse, lambda msg: cb_parse(msg, pub))
00368     rospy.loginfo("semantic_framer: Services up.")
00369 
00370     rospy.spin()
00371 
00372 if __name__ == '__main__':
00373     main()
00374 
00375 
00376 
00377 
00378 
00379 
00380 
00381 
00382 
00383 
00384 
00385 
00386 


semantic_framer
Author(s): Brian Thomas
autogenerated on Fri Dec 6 2013 20:39:14