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
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef __SOUND_PLAY__SOUND_PLAY__H__
00038 #define __SOUND_PLAY__SOUND_PLAY__H__
00039
00040 #include <string>
00041 #include <ros/ros.h>
00042 #include <ros/node_handle.h>
00043 #include <sound_play/SoundRequest.h>
00044 #include <boost/thread.hpp>
00045
00046 namespace sound_play
00047 {
00048
00062 class SoundClient
00063 {
00064 public:
00065 class Sound
00066 {
00067 friend class SoundClient;
00068 private:
00069 int snd_;
00070 std::string arg_;
00071 SoundClient *client_;
00072
00073 Sound(SoundClient *sc, int snd, const std::string &arg)
00074 {
00075 client_ = sc;
00076 snd_ = snd;
00077 arg_ = arg;
00078 }
00079
00080 public:
00087 void play()
00088 {
00089 client_->sendMsg(snd_, SoundRequest::PLAY_ONCE, arg_);
00090 }
00091
00099 void repeat()
00100 {
00101 client_->sendMsg(snd_, SoundRequest::PLAY_START, arg_);
00102 }
00103
00110 void stop()
00111 {
00112 client_->sendMsg(snd_, SoundRequest::PLAY_STOP, arg_);
00113 }
00114 };
00115
00126 SoundClient(ros::NodeHandle &nh, const std::string &topic)
00127 {
00128 init(nh, topic);
00129 }
00130
00136 SoundClient()
00137 {
00138 init(ros::NodeHandle(), "robotsound");
00139 }
00140
00149 Sound voiceSound(const std::string &s)
00150 {
00151 return Sound(this, SoundRequest::SAY, s);
00152 }
00153
00163 Sound waveSound(const std::string &s)
00164 {
00165 return Sound(this, SoundRequest::PLAY_FILE, s);
00166 }
00167
00176 Sound builtinSound(int id)
00177 {
00178 return Sound(this, id, "");
00179 }
00180
00189 void say(const std::string &s, const std::string &voice="voice_kal_diphone")
00190 {
00191 sendMsg(SoundRequest::SAY, SoundRequest::PLAY_ONCE, s, voice);
00192 }
00193
00201 void repeat(const std::string &s)
00202 {
00203 sendMsg(SoundRequest::SAY, SoundRequest::PLAY_START, s);
00204 }
00205
00214 void stopSaying(const std::string &s)
00215 {
00216 sendMsg(SoundRequest::SAY, SoundRequest::PLAY_STOP, s);
00217 }
00218
00228 void playWave(const std::string &s)
00229 {
00230 sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_ONCE, s);
00231 }
00232
00241 void startWave(const std::string &s)
00242 {
00243 sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_START, s);
00244 }
00245
00254 void stopWave(const std::string &s)
00255 {
00256 sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_STOP, s);
00257 }
00258
00267 void play(int sound)
00268 {
00269 sendMsg(sound, SoundRequest::PLAY_ONCE);
00270 }
00271
00280 void start(int sound)
00281 {
00282 sendMsg(sound, SoundRequest::PLAY_START);
00283 }
00284
00292 void stop(int sound)
00293 {
00294 sendMsg(sound, SoundRequest::PLAY_STOP);
00295 }
00296
00302 void stopAll()
00303 {
00304 stop(SoundRequest::ALL);
00305 }
00306
00316 void setQuiet(bool state)
00317 {
00318 quiet_ = state;
00319 }
00320
00321 private:
00322 void init(ros::NodeHandle nh, const std::string &topic)
00323 {
00324 nh_ = nh;
00325 pub_ = nh.advertise<sound_play::SoundRequest>(topic, 5);
00326 quiet_ = false;
00327 }
00328
00329 void sendMsg(int snd, int cmd, const std::string &s = "", const std::string &arg2 = "")
00330 {
00331 boost::mutex::scoped_lock lock(mutex_);
00332
00333 if (!nh_.ok())
00334 return;
00335
00336 SoundRequest msg;
00337 msg.sound = snd;
00338 msg.command = cmd;
00339 msg.arg = s;
00340 msg.arg2 = arg2;
00341 pub_.publish(msg);
00342
00343 if (pub_.getNumSubscribers() == 0 && !quiet_)
00344 ROS_WARN("Sound command issued, but no node is subscribed to the topic. Perhaps you forgot to run soundplay_node.py");
00345 }
00346
00347 bool quiet_;
00348 ros::NodeHandle nh_;
00349 ros::Publisher pub_;
00350 boost::mutex mutex_;
00351 };
00352
00353 typedef SoundClient::Sound Sound;
00354
00355 };
00356
00357 #endif