src
subscribers
speech.hpp
Go to the documentation of this file.
1
/*
2
* Copyright 2015 Aldebaran
3
*
4
* Licensed under the Apache License, Version 2.0 (the "License");
5
* you may not use this file except in compliance with the License.
6
* You may obtain a copy of the License at
7
*
8
* http://www.apache.org/licenses/LICENSE-2.0
9
*
10
* Unless required by applicable law or agreed to in writing, software
11
* distributed under the License is distributed on an "AS IS" BASIS,
12
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13
* See the License for the specific language governing permissions and
14
* limitations under the License.
15
*
16
*/
17
18
19
#ifndef SPEECH_SUBSCRIBER_HPP
20
#define SPEECH_SUBSCRIBER_HPP
21
22
/*
23
* LOCAL includes
24
*/
25
#include "
subscriber_base.hpp
"
26
27
/*
28
* ROS includes
29
*/
30
#include <
ros/ros.h
>
31
#include <std_msgs/String.h>
32
33
namespace
naoqi
34
{
35
namespace
subscriber
36
{
37
38
class
SpeechSubscriber
:
public
BaseSubscriber
<SpeechSubscriber>
39
{
40
public
:
41
SpeechSubscriber
(
const
std::string&
name
,
const
std::string& speech_topic,
const
qi::SessionPtr&
session
);
42
~SpeechSubscriber
(){}
43
44
void
reset
(
ros::NodeHandle
& nh );
45
void
speech_callback
(
const
std_msgs::StringConstPtr& speech_msg );
46
47
private
:
48
49
std::string
speech_topic_
;
50
51
qi::AnyObject
p_tts_
;
52
ros::Subscriber
sub_speech_
;
53
54
55
56
};
// class Speech
57
58
}
// subscriber
59
}
// naoqi
60
#endif
naoqi::subscriber::BaseSubscriber
Definition:
subscriber_base.hpp:39
naoqi::subscriber::BaseSubscriber< SpeechSubscriber >::name
std::string name() const
Definition:
subscriber_base.hpp:53
naoqi::subscriber::SpeechSubscriber::sub_speech_
ros::Subscriber sub_speech_
Definition:
speech.hpp:52
ros.h
session
session
naoqi::subscriber::SpeechSubscriber::reset
void reset(ros::NodeHandle &nh)
Definition:
speech.cpp:35
naoqi::subscriber::SpeechSubscriber::~SpeechSubscriber
~SpeechSubscriber()
Definition:
speech.hpp:42
naoqi
Definition:
converter.hpp:29
naoqi::subscriber::SpeechSubscriber
Definition:
speech.hpp:38
subscriber_base.hpp
naoqi::subscriber::SpeechSubscriber::speech_topic_
std::string speech_topic_
Definition:
speech.hpp:49
naoqi::subscriber::SpeechSubscriber::speech_callback
void speech_callback(const std_msgs::StringConstPtr &speech_msg)
Definition:
speech.cpp:42
naoqi::subscriber::SpeechSubscriber::p_tts_
qi::AnyObject p_tts_
Definition:
speech.hpp:51
ros::NodeHandle
ros::Subscriber
naoqi::subscriber::SpeechSubscriber::SpeechSubscriber
SpeechSubscriber(const std::string &name, const std::string &speech_topic, const qi::SessionPtr &session)
Definition:
speech.cpp:29
naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 3 2024 03:50:06