Go to the documentation of this file.00001
00002
00003
00004 try:
00005 import roslib; roslib,load_manifest('rospeex_if')
00006 except:
00007 pass
00008
00009 import rospy
00010 import re
00011
00012 from rospeex_if import ROSpeexInterface
00013 from std_msgs.msg import String
00014
00015 syscommand_pub = rospy.Publisher('syscommand', String, queue_size=10)
00016 rospy.init_node('navigation_strategy', anonymous=True)
00017 r = rospy.Rate(10)
00018
00019 class talk_node(object):
00020
00021 def __init__(self):
00022
00023 self._interface = ROSpeexInterface()
00024
00025 def sr_response(self, message):
00026
00027 run = re.compile('(?P<run>走行)').search(message)
00028 start = re.compile('(?P<start>開始)').search(message)
00029
00030 print 'you said : %s' %message
00031
00032 if run is not None and start is not None:
00033 text = u'ナビゲーションを開始します。'
00034 robot_msg = 'start'
00035
00036 rospy.loginfo(robot_msg)
00037 syscommand_pub.publish(robot_msg)
00038
00039
00040 print 'rospeex reply : %s' %text
00041 self._interface.say(text, 'ja', 'nict')
00042
00043 def run(self):
00044 self._interface.init()
00045 self._interface.register_sr_response(self.sr_response)
00046 self._interface.set_spi_config(language='ja',engine='nict')
00047 rospy.spin()
00048
00049 if __name__ == '__main__':
00050 try:
00051 node = talk_node()
00052 node.run()
00053 except rospy.ROSInterruptException:
00054 pass