Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021 #include "speech.hpp"
00022
00023
00024 namespace naoqi
00025 {
00026 namespace subscriber
00027 {
00028
00029 SpeechSubscriber::SpeechSubscriber( const std::string& name, const std::string& speech_topic, const qi::SessionPtr& session ):
00030 speech_topic_(speech_topic),
00031 BaseSubscriber( name, speech_topic, session ),
00032 p_tts_( session->service("ALTextToSpeech") )
00033 {}
00034
00035 void SpeechSubscriber::reset( ros::NodeHandle& nh )
00036 {
00037 sub_speech_ = nh.subscribe( speech_topic_, 10, &SpeechSubscriber::speech_callback, this );
00038
00039 is_initialized_ = true;
00040 }
00041
00042 void SpeechSubscriber::speech_callback( const std_msgs::StringConstPtr& string_msg )
00043 {
00044 p_tts_.async<void>("say", string_msg->data);
00045 }
00046
00047 }
00048 }