TOP > Talking Watch サンプル

Talking Watch サンプル

概要

このサンプルでは、「ロボット今何時?」と音声入力したときに、現在時刻を音声で出力します。 <python版> ( cpp版はこちら )

実行結果

プログラムの起動

端末から音声認識用の波形モニタを起動します。

$ source ~/catkin_ws/devel_isolated/setup.bash
$ rosrun rospeex_audiomonitor audio_monitor_epd

新しい端末を開き、サンプルを起動します。

$ source ~/catkin_ws/devel_isolated/setup.bash
$ roslaunch rospeex_samples talking_watch_python_ja_local.launch

操作

起動後、マイクに「ロボット今何時?」と言ってください。正常に認識された場合、「○○時○○分です。」と答えます。

実装

以下のコードでTalking Watch サンプルを作成できます。

実装(python) :

#!/usr/bin/env python
# -*- coding: utf-8 -*-

try:
    import roslib; roslib.load_manifest('rospeex_if')
except:
    pass

import rospy
import datetime
import re

# Import other libraries
from rospeex_if import ROSpeexInterface

class Demo(object):
    """ Demo class """
    def __init__(self):
        """ Initializer """
        self._interface = ROSpeexInterface()

    def sr_response(self, message):
        """ speech recognition response callback
        @param message: recognize result (e.g. what time is it ?)
        @type  message: str
        """
        time = re.compile('(?P<time>何時)').search(message)

        print 'you said : %s' % message
        if time is not None:
            d = datetime.datetime.today()
            text = u'%d時%d分です。'%(d.hour, d.minute)

            # rospeex reply
            print 'rospeex reply : %s' %text
            self._interface.say(text, 'ja', 'nict')

    def run(self):
        """ run ros node """
        # initialize ros node
        rospy.init_node('ss_sr_demo')

        # initialize rospeex
        self._interface.init()
        self._interface.register_sr_response(self.sr_response)
        self._interface.set_spi_config(language='ja',engine='nict')
        rospy.spin()

if __name__ == '__main__':
    try:
        node = Demo()
        node.run()
    except rospy.ROSInterruptException:
        pass