src
subscribers
speech.cpp
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
* LOCAL includes
20
*/
21
#include "
speech.hpp
"
22
23
24
namespace
naoqi
25
{
26
namespace
subscriber
27
{
28
29
SpeechSubscriber::SpeechSubscriber
(
const
std::string& name,
const
std::string& speech_topic,
const
qi::SessionPtr& session ):
30
speech_topic_(speech_topic),
31
BaseSubscriber
(
name
, speech_topic,
session
),
32
p_tts_(
session
->service(
"ALTextToSpeech"
).value())
33
{}
34
35
void
SpeechSubscriber::reset
(
ros::NodeHandle
& nh )
36
{
37
sub_speech_
= nh.
subscribe
(
speech_topic_
, 10, &
SpeechSubscriber::speech_callback
,
this
);
38
39
is_initialized_
=
true
;
40
}
41
42
void
SpeechSubscriber::speech_callback
(
const
std_msgs::StringConstPtr& string_msg )
43
{
44
p_tts_
.async<
void
>(
"say"
, string_msg->data);
45
}
46
47
}
//publisher
48
}
// naoqi
naoqi::subscriber::BaseSubscriber
Definition:
subscriber_base.hpp:39
naoqi::subscriber::SpeechSubscriber::sub_speech_
ros::Subscriber sub_speech_
Definition:
speech.hpp:52
session
session
naoqi::subscriber::SpeechSubscriber::reset
void reset(ros::NodeHandle &nh)
Definition:
speech.cpp:35
naoqi
Definition:
converter.hpp:29
naoqi::subscriber::BaseSubscriber< SpeechSubscriber >::is_initialized_
bool is_initialized_
Definition:
subscriber_base.hpp:71
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
name
name
speech.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
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