Go to the documentation of this file.00001
00002 import roslib; roslib.load_manifest('rfnserver')
00003 import rospy
00004 import actionlib
00005 import os
00006 from actionlib import SimpleActionServer
00007 from roboframenet_msgs.msg import FilledSemanticFrameAction
00008 from roboframenet_msgs.srv import AddFrame, AddLexicalUnit, RegisterWithFrame
00009
00010
00011 class RFNServer(SimpleActionServer):
00012 def __init__(self, callback_topic, callback_function):
00013
00014 SimpleActionServer.__init__(self,
00015 callback_topic,
00016 FilledSemanticFrameAction,
00017
00018
00019 lambda semantic_frame_goal:
00020 callback_function(semantic_frame_goal.frame),
00021 False)
00022 self.callback_topic = callback_topic
00023 self.callback_function = callback_function
00024
00025
00026 def add_frame(self, filepath):
00027 rospy.wait_for_service('add_frame')
00028 try:
00029 srv = rospy.ServiceProxy('add_frame', AddFrame)
00030 result = srv(os.path.abspath(filepath))
00031 except rospy.ServiceException, e:
00032 print "Service call failed: %s"%e
00033 return False
00034 return result
00035
00036
00037
00038 def add_lexical_unit(self, filepath):
00039 rospy.wait_for_service('add_lexical_unit')
00040 try:
00041 srv = rospy.ServiceProxy('add_lexical_unit', AddLexicalUnit)
00042 result = srv(os.path.abspath(filepath))
00043 except rospy.ServiceException, e:
00044 print "Service call failed: %s"%e
00045 return False
00046 return result
00047
00048
00049
00050 def register_with_frame(self, frame_name):
00051 rospy.wait_for_service('register_with_frame')
00052 try:
00053 srv = rospy.ServiceProxy('register_with_frame', RegisterWithFrame)
00054 result = srv(frame_name, self.callback_topic)
00055 except rospy.ServiceException, e:
00056 print "Service call failed: %s"%e
00057 return False
00058 return result.success
00059
00060
00061 @staticmethod
00062 def frame_argument(filled_semantic_frame, parameter_name):
00063 for fe in filled_semantic_frame.frame_elements:
00064 if fe.name == parameter_name:
00065 return fe.argument
00066 return False