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 std::string arg2_;
00072 SoundClient *client_;
00073
00074 Sound(SoundClient *sc, int snd, const std::string &arg, const std::string arg2 = std::string())
00075 {
00076 client_ = sc;
00077 snd_ = snd;
00078 arg_ = arg;
00079 arg2_ = arg2;
00080 }
00081
00082 public:
00089 void play()
00090 {
00091 client_->sendMsg(snd_, SoundRequest::PLAY_ONCE, arg_, arg2_);
00092 }
00093
00101 void repeat()
00102 {
00103 client_->sendMsg(snd_, SoundRequest::PLAY_START, arg_, arg2_);
00104 }
00105
00112 void stop()
00113 {
00114 client_->sendMsg(snd_, SoundRequest::PLAY_STOP, arg_, arg2_);
00115 }
00116 };
00117
00128 SoundClient(ros::NodeHandle &nh, const std::string &topic)
00129 {
00130 init(nh, topic);
00131 }
00132
00138 SoundClient()
00139 {
00140 init(ros::NodeHandle(), "robotsound");
00141 }
00142
00151 Sound voiceSound(const std::string &s)
00152 {
00153 return Sound(this, SoundRequest::SAY, s);
00154 }
00155
00165 Sound waveSound(const std::string &s)
00166 {
00167 return Sound(this, SoundRequest::PLAY_FILE, s);
00168 }
00169
00180 Sound waveSoundFromPkg(const std::string &p, const std::string &s)
00181 {
00182 return Sound(this, SoundRequest::PLAY_FILE, s, p);
00183 }
00184
00193 Sound builtinSound(int id)
00194 {
00195 return Sound(this, id, "");
00196 }
00197
00206 void say(const std::string &s, const std::string &voice="voice_kal_diphone")
00207 {
00208 sendMsg(SoundRequest::SAY, SoundRequest::PLAY_ONCE, s, voice);
00209 }
00210
00218 void repeat(const std::string &s)
00219 {
00220 sendMsg(SoundRequest::SAY, SoundRequest::PLAY_START, s);
00221 }
00222
00231 void stopSaying(const std::string &s)
00232 {
00233 sendMsg(SoundRequest::SAY, SoundRequest::PLAY_STOP, s);
00234 }
00235
00245 void playWave(const std::string &s)
00246 {
00247 sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_ONCE, s);
00248 }
00249
00258 void startWave(const std::string &s)
00259 {
00260 sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_START, s);
00261 }
00262
00271 void stopWave(const std::string &s)
00272 {
00273 sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_STOP, s);
00274 }
00275
00286 void playWaveFromPkg(const std::string &p, const std::string &s)
00287 {
00288 sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_ONCE, s, p);
00289 }
00290
00300 void startWaveFromPkg(const std::string &p, const std::string &s)
00301 {
00302 sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_START, s, p);
00303 }
00304
00315 void stopWaveFromPkg(const std::string &p, const std::string &s)
00316 {
00317 sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_STOP, s, p);
00318 }
00319
00328 void play(int sound)
00329 {
00330 sendMsg(sound, SoundRequest::PLAY_ONCE);
00331 }
00332
00341 void start(int sound)
00342 {
00343 sendMsg(sound, SoundRequest::PLAY_START);
00344 }
00345
00353 void stop(int sound)
00354 {
00355 sendMsg(sound, SoundRequest::PLAY_STOP);
00356 }
00357
00363 void stopAll()
00364 {
00365 stop(SoundRequest::ALL);
00366 }
00367
00377 void setQuiet(bool state)
00378 {
00379 quiet_ = state;
00380 }
00381
00382 private:
00383 void init(ros::NodeHandle nh, const std::string &topic)
00384 {
00385 nh_ = nh;
00386 pub_ = nh.advertise<sound_play::SoundRequest>(topic, 5);
00387 quiet_ = false;
00388 }
00389
00390 void sendMsg(int snd, int cmd, const std::string &s = "", const std::string &arg2 = "")
00391 {
00392 boost::mutex::scoped_lock lock(mutex_);
00393
00394 if (!nh_.ok())
00395 return;
00396
00397 SoundRequest msg;
00398 msg.sound = snd;
00399 msg.command = cmd;
00400 msg.arg = s;
00401 msg.arg2 = arg2;
00402 pub_.publish(msg);
00403
00404 if (pub_.getNumSubscribers() == 0 && !quiet_)
00405 ROS_WARN("Sound command issued, but no node is subscribed to the topic. Perhaps you forgot to run soundplay_node.py");
00406 }
00407
00408 bool quiet_;
00409 ros::NodeHandle nh_;
00410 ros::Publisher pub_;
00411 boost::mutex mutex_;
00412 };
00413
00414 typedef SoundClient::Sound Sound;
00415
00416 };
00417
00418 #endif