Skip to content

Commit

Permalink
Merge pull request #43 from k-okada/add_speech
Browse files Browse the repository at this point in the history
[WIP] add subscribers/speech.cpp
  • Loading branch information
Karsten1987 committed Oct 25, 2015
2 parents de8444e + 1a847e0 commit 7107140
Show file tree
Hide file tree
Showing 4 changed files with 111 additions and 0 deletions.
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ set(
SUBSCRIBER_SRC
src/subscribers/teleop.cpp
src/subscribers/moveto.cpp
src/subscribers/speech.cpp
)

set(
Expand Down
2 changes: 2 additions & 0 deletions src/naoqi_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,7 @@
*/
#include "subscribers/teleop.hpp"
#include "subscribers/moveto.hpp"
#include "subscribers/speech.hpp"


/*
Expand Down Expand Up @@ -787,6 +788,7 @@ void Driver::registerDefaultSubscriber()
return;
registerSubscriber( boost::make_shared<naoqi::subscriber::TeleopSubscriber>("teleop", "/cmd_vel", "/joint_angles", sessionPtr_) );
registerSubscriber( boost::make_shared<naoqi::subscriber::MovetoSubscriber>("moveto", "/move_base_simple/goal", sessionPtr_, tf2_buffer_) );
registerSubscriber( boost::make_shared<naoqi::subscriber::SpeechSubscriber>("speech", "/speech", sessionPtr_) );
}

void Driver::registerService( service::Service srv )
Expand Down
48 changes: 48 additions & 0 deletions src/subscribers/speech.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
/*
* Copyright 2015 Aldebaran
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

/*
* LOCAL includes
*/
#include "speech.hpp"


namespace naoqi
{
namespace subscriber
{

SpeechSubscriber::SpeechSubscriber( const std::string& name, const std::string& speech_topic, const qi::SessionPtr& session ):
speech_topic_(speech_topic),
BaseSubscriber( name, speech_topic, session ),
p_tts_( session->service("ALTextToSpeech") )
{}

void SpeechSubscriber::reset( ros::NodeHandle& nh )
{
sub_speech_ = nh.subscribe( speech_topic_, 10, &SpeechSubscriber::speech_callback, this );

is_initialized_ = true;
}

void SpeechSubscriber::speech_callback( const std_msgs::StringConstPtr& string_msg )
{
p_tts_.async<void>("say", string_msg->data);
}

} //publisher
} // naoqi
60 changes: 60 additions & 0 deletions src/subscribers/speech.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
/*
* Copyright 2015 Aldebaran
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/


#ifndef SPEECH_SUBSCRIBER_HPP
#define SPEECH_SUBSCRIBER_HPP

/*
* LOCAL includes
*/
#include "subscriber_base.hpp"

/*
* ROS includes
*/
#include <ros/ros.h>
#include <std_msgs/String.h>

namespace naoqi
{
namespace subscriber
{

class SpeechSubscriber: public BaseSubscriber<SpeechSubscriber>
{
public:
SpeechSubscriber( const std::string& name, const std::string& speech_topic, const qi::SessionPtr& session );
~SpeechSubscriber(){}

void reset( ros::NodeHandle& nh );
void speech_callback( const std_msgs::StringConstPtr& speech_msg );

private:

std::string speech_topic_;

qi::AnyObject p_tts_;
ros::Subscriber sub_speech_;



}; // class Speech

} // subscriber
}// naoqi
#endif

0 comments on commit 7107140

Please sign in to comment.