37 #ifndef __SOUND_PLAY__SOUND_PLAY__H__ 38 #define __SOUND_PLAY__SOUND_PLAY__H__ 43 #include <sound_play/SoundRequest.h> 44 #include <boost/thread.hpp> 74 Sound(
SoundClient *sc,
int snd,
const std::string &arg,
const std::string arg2 = std::string(),
const float vol = 1.0f)
90 client_->
sendMsg(snd_, SoundRequest::PLAY_ONCE, arg_, arg2_, vol_);
100 client_->
sendMsg(snd_, SoundRequest::PLAY_START, arg_, arg2_, vol_);
109 client_->
sendMsg(snd_, SoundRequest::PLAY_STOP, arg_, arg2_, vol_);
145 return Sound(
this, SoundRequest::SAY, s,
"",
volume);
158 return Sound(
this, SoundRequest::PLAY_FILE, s,
"",
volume);
172 return Sound(
this, SoundRequest::PLAY_FILE, s, p,
volume);
195 void say(
const std::string &
s,
const std::string &
voice=
"voice_kal_diphone",
float volume = 1.0f)
209 sendMsg(SoundRequest::SAY, SoundRequest::PLAY_START, s,
"",
volume);
221 sendMsg(SoundRequest::SAY, SoundRequest::PLAY_STOP, s,
"");
235 sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_ONCE, s,
"",
volume);
248 sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_START, s,
"",
volume);
260 sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_STOP, s);
275 sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_ONCE, s, p,
volume);
289 sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_START, s, p,
volume);
303 sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_STOP, s, p);
340 sendMsg(sound, SoundRequest::PLAY_STOP);
349 stop(SoundRequest::ALL);
373 void sendMsg(
int snd,
int cmd,
const std::string &
s =
"",
const std::string &arg2 =
"",
const float &vol = 1.0f)
375 boost::mutex::scoped_lock lock(
mutex_);
397 ROS_WARN(
"Sound command issued, but no node is subscribed to the topic. Perhaps you forgot to run soundplay_node.py");
void play(int sound, float volume=1.0f)
Play a buildin sound.
void playWaveFromPkg(const std::string &p, const std::string &s, float volume=1.0f)
Plays a WAV or OGG file from a package.
void publish(const boost::shared_ptr< M > &message) const
void repeat()
Play the Sound repeatedly.
void sendMsg(int snd, int cmd, const std::string &s="", const std::string &arg2="", const float &vol=1.0f)
void repeat(const std::string &s, float volume=1.0f)
Say a string repeatedly.
void stopAll()
Stop all currently playing sounds.
void stopSaying(const std::string &s)
Stop saying a string.
void stopWaveFromPkg(const std::string &p, const std::string &s)
Stop playing a WAV or OGG file.
void startWave(const std::string &s, float volume=1.0f)
Plays a WAV or OGG file repeatedly.
Sound builtinSound(int id, float volume=1.0f)
Create a builtin Sound.
void play()
Play the Sound.
SoundClient(ros::NodeHandle &nh, const std::string &topic)
Create a SoundClient that publishes on the given topic.
Sound waveSoundFromPkg(const std::string &p, const std::string &s, float volume=1.0f)
Create a wave Sound from a package.
void start(int sound, float volume=1.0f)
Play a buildin sound repeatedly.
void startWaveFromPkg(const std::string &p, const std::string &s, float volume=1.0f)
Plays a WAV or OGG file repeatedly.
Sound waveSound(const std::string &s, float volume=1.0f)
Create a wave Sound.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
SoundClient()
Create a SoundClient with the default topic.
Sound voiceSound(const std::string &s, float volume=1.0f)
Create a voice Sound.
void stopWave(const std::string &s)
Stop playing a WAV or OGG file.
void say(const std::string &s, const std::string &voice="voice_kal_diphone", float volume=1.0f)
Say a string.
uint32_t getNumSubscribers() const
void setQuiet(bool state)
Turns warning messages on or off.
void playWave(const std::string &s, float volume=1.0f)
Plays a WAV or OGG file.
Class that publishes messages to the sound_play node.
void init(ros::NodeHandle nh, const std::string &topic)
Sound(SoundClient *sc, int snd, const std::string &arg, const std::string arg2=std::string(), const float vol=1.0f)
void stop()
Stop Sound playback.
void stop(int sound)
Stop playing a built-in sound.