#include <speech.hpp>

| Public Member Functions | |
| void | reset (ros::NodeHandle &nh) | 
| void | speech_callback (const std_msgs::StringConstPtr &speech_msg) | 
| SpeechSubscriber (const std::string &name, const std::string &speech_topic, const qi::SessionPtr &session) | |
| ~SpeechSubscriber () | |
|  Public Member Functions inherited from naoqi::subscriber::BaseSubscriber< SpeechSubscriber > | |
| BaseSubscriber (const std::string &name, const std::string &topic, qi::SessionPtr session) | |
| bool | isInitialized () const | 
| std::string | name () const | 
| std::string | topic () const | 
| virtual | ~BaseSubscriber () | 
| Private Attributes | |
| qi::AnyObject | p_tts_ | 
| std::string | speech_topic_ | 
| ros::Subscriber | sub_speech_ | 
| Additional Inherited Members | |
|  Protected Attributes inherited from naoqi::subscriber::BaseSubscriber< SpeechSubscriber > | |
| bool | is_initialized_ | 
| std::string | name_ | 
| const robot::Robot & | robot_ | 
| qi::SessionPtr | session_ | 
| std::string | topic_ | 
Definition at line 38 of file speech.hpp.
| naoqi::subscriber::SpeechSubscriber::SpeechSubscriber | ( | const std::string & | name, | 
| const std::string & | speech_topic, | ||
| const qi::SessionPtr & | session | ||
| ) | 
Definition at line 29 of file speech.cpp.
| 
 | inline | 
Definition at line 42 of file speech.hpp.
| void naoqi::subscriber::SpeechSubscriber::reset | ( | ros::NodeHandle & | nh | ) | 
Definition at line 35 of file speech.cpp.
| void naoqi::subscriber::SpeechSubscriber::speech_callback | ( | const std_msgs::StringConstPtr & | speech_msg | ) | 
Definition at line 42 of file speech.cpp.
| 
 | private | 
Definition at line 51 of file speech.hpp.
| 
 | private | 
Definition at line 49 of file speech.hpp.
| 
 | private | 
Definition at line 52 of file speech.hpp.