$search
00001 #!/usr/bin/python 00002 import roslib; roslib.load_manifest('oro_chatter') 00003 import rospy 00004 import json 00005 from std_msgs.msg import String 00006 from oro_ros.srv import * 00007 from web_hri.srv import * 00008 00009 def callback(data): 00010 try: 00011 rospy.loginfo("Got input: " + data.data) 00012 oro_resp = process_nl(["\"" + data.data + "\""]) 00013 00014 try: 00015 if (oro_resp.res[1:-1] != ""): 00016 rospy.loginfo("ORO answered: " + oro_resp.res) 00017 tell_human(oro_resp.res[1:-1]) 00018 else: 00019 rospy.loginfo("ORO didn't understand") 00020 00021 except rospy.ServiceException, e: 00022 rospy.logerr("I couldn't send back ORO's answer to the human!") 00023 00024 except rospy.ServiceException, e: 00025 rospy.logerr("ORO could not process request: %s"%str(e)) 00026 00027 00028 def listener(): 00029 rospy.init_node('oro_listener', anonymous=True) 00030 rospy.Subscriber("/hri/listen_human", String, callback) 00031 rospy.spin() 00032 00033 if __name__ == '__main__': 00034 rospy.wait_for_service('/oro/processNL') 00035 process_nl = rospy.ServiceProxy('/oro/processNL', OroServerQuery) 00036 00037 rospy.wait_for_service('/hri/tell_human') 00038 tell_human = rospy.ServiceProxy('/hri/tell_human', AskHuman) 00039 00040 listener()