sound_play.h
Go to the documentation of this file.
1 /*
2  ***********************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2009, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  ***********************************************************
35  */
36 
37 #ifndef __SOUND_PLAY__SOUND_PLAY__H__
38 #define __SOUND_PLAY__SOUND_PLAY__H__
39 
40 #include <string>
41 #include <ros/ros.h>
42 #include <ros/node_handle.h>
43 #include <sound_play/SoundRequest.h>
44 #include <boost/thread.hpp>
45 
46 namespace sound_play
47 {
48 
62 {
63 public:
64  class Sound
65  {
66  friend class SoundClient;
67  private:
68  int snd_;
69  float vol_;
70  std::string arg_;
71  std::string arg2_;
73 
74  Sound(SoundClient *sc, int snd, const std::string &arg, const std::string arg2 = std::string(), const float vol = 1.0f)
75  {
76  client_ = sc;
77  snd_ = snd;
78  arg_ = arg;
79  arg2_ = arg2;
80  vol_ = vol;
81  }
82 
83  public:
88  void play()
89  {
90  client_->sendMsg(snd_, SoundRequest::PLAY_ONCE, arg_, arg2_, vol_);
91  }
92 
98  void repeat()
99  {
100  client_->sendMsg(snd_, SoundRequest::PLAY_START, arg_, arg2_, vol_);
101  }
102 
107  void stop()
108  {
109  client_->sendMsg(snd_, SoundRequest::PLAY_STOP, arg_, arg2_, vol_);
110  }
111  };
112 
122  SoundClient(ros::NodeHandle &nh, const std::string &topic)
123  {
124  init(nh, topic);
125  }
126 
132  {
133  init(ros::NodeHandle(), "robotsound");
134  }
135 
143  Sound voiceSound(const std::string &s, float volume = 1.0f)
144  {
145  return Sound(this, SoundRequest::SAY, s, "", volume);
146  }
147 
156  Sound waveSound(const std::string &s, float volume = 1.0f)
157  {
158  return Sound(this, SoundRequest::PLAY_FILE, s, "", volume);
159  }
160 
170  Sound waveSoundFromPkg(const std::string &p, const std::string &s, float volume = 1.0f)
171  {
172  return Sound(this, SoundRequest::PLAY_FILE, s, p, volume);
173  }
174 
182  Sound builtinSound(int id, float volume = 1.0f)
183  {
184  return Sound(this, id, "", "", volume);
185  }
186 
195  void say(const std::string &s, const std::string &voice="voice_kal_diphone", float volume = 1.0f)
196  {
197  sendMsg(SoundRequest::SAY, SoundRequest::PLAY_ONCE, s, voice, volume);
198  }
199 
207  void repeat(const std::string &s, float volume = 1.0f)
208  {
209  sendMsg(SoundRequest::SAY, SoundRequest::PLAY_START, s, "", volume);
210  }
211 
219  void stopSaying(const std::string &s)
220  {
221  sendMsg(SoundRequest::SAY, SoundRequest::PLAY_STOP, s, "");
222  }
223 
233  void playWave(const std::string &s, float volume = 1.0f)
234  {
235  sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_ONCE, s, "", volume);
236  }
237 
246  void startWave(const std::string &s, float volume = 1.0f)
247  {
248  sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_START, s, "", volume);
249  }
250 
258  void stopWave(const std::string &s)
259  {
260  sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_STOP, s);
261  }
262 
273  void playWaveFromPkg(const std::string &p, const std::string &s, float volume = 1.0f)
274  {
275  sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_ONCE, s, p, volume);
276  }
277 
287  void startWaveFromPkg(const std::string &p, const std::string &s, float volume = 1.0f)
288  {
289  sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_START, s, p, volume);
290  }
291 
301  void stopWaveFromPkg(const std::string &p, const std::string &s)
302  {
303  sendMsg(SoundRequest::PLAY_FILE, SoundRequest::PLAY_STOP, s, p);
304  }
305 
314  void play(int sound, float volume = 1.0f)
315  {
316  sendMsg(sound, SoundRequest::PLAY_ONCE, "", "", volume);
317  }
318 
327  void start(int sound, float volume = 1.0f)
328  {
329  sendMsg(sound, SoundRequest::PLAY_START, "", "", volume);
330  }
331 
338  void stop(int sound)
339  {
340  sendMsg(sound, SoundRequest::PLAY_STOP);
341  }
342 
347  void stopAll()
348  {
349  stop(SoundRequest::ALL);
350  }
351 
360  void setQuiet(bool state)
361  {
362  quiet_ = state;
363  }
364 
365 private:
366  void init(ros::NodeHandle nh, const std::string &topic)
367  {
368  nh_ = nh;
369  pub_ = nh.advertise<sound_play::SoundRequest>(topic, 5);
370  quiet_ = false;
371  }
372 
373  void sendMsg(int snd, int cmd, const std::string &s = "", const std::string &arg2 = "", const float &vol = 1.0f)
374  {
375  boost::mutex::scoped_lock lock(mutex_);
376 
377  if (!nh_.ok())
378  return;
379 
380  SoundRequest msg;
381  msg.sound = snd;
382  msg.command = cmd;
383  msg.arg = s;
384  msg.arg2 = arg2;
385 
386  // ensure volume is in the correct range
387  if (vol < 0)
388  msg.volume = 0;
389  else if (vol > 1.0)
390  msg.volume = 1.0f;
391  else
392  msg.volume = vol;
393 
394  pub_.publish(msg);
395 
396  if (pub_.getNumSubscribers() == 0 && !quiet_)
397  ROS_WARN("Sound command issued, but no node is subscribed to the topic. Perhaps you forgot to run soundplay_node.py");
398  }
399 
400  bool quiet_;
403  boost::mutex mutex_;
404 };
405 
407 
408 };
409 
410 #endif
void play(int sound, float volume=1.0f)
Play a buildin sound.
Definition: sound_play.h:314
void playWaveFromPkg(const std::string &p, const std::string &s, float volume=1.0f)
Plays a WAV or OGG file from a package.
Definition: sound_play.h:273
void publish(const boost::shared_ptr< M > &message) const
void repeat()
Play the Sound repeatedly.
Definition: sound_play.h:98
ros::NodeHandle nh_
Definition: sound_play.h:401
void sendMsg(int snd, int cmd, const std::string &s="", const std::string &arg2="", const float &vol=1.0f)
Definition: sound_play.h:373
void repeat(const std::string &s, float volume=1.0f)
Say a string repeatedly.
Definition: sound_play.h:207
void stopAll()
Stop all currently playing sounds.
Definition: sound_play.h:347
s
Definition: say.py:70
int volume
Definition: play.py:59
void stopSaying(const std::string &s)
Stop saying a string.
Definition: sound_play.h:219
void stopWaveFromPkg(const std::string &p, const std::string &s)
Stop playing a WAV or OGG file.
Definition: sound_play.h:301
#define ROS_WARN(...)
void startWave(const std::string &s, float volume=1.0f)
Plays a WAV or OGG file repeatedly.
Definition: sound_play.h:246
Sound builtinSound(int id, float volume=1.0f)
Create a builtin Sound.
Definition: sound_play.h:182
void play()
Play the Sound.
Definition: sound_play.h:88
SoundClient(ros::NodeHandle &nh, const std::string &topic)
Create a SoundClient that publishes on the given topic.
Definition: sound_play.h:122
Sound waveSoundFromPkg(const std::string &p, const std::string &s, float volume=1.0f)
Create a wave Sound from a package.
Definition: sound_play.h:170
void start(int sound, float volume=1.0f)
Play a buildin sound repeatedly.
Definition: sound_play.h:327
void startWaveFromPkg(const std::string &p, const std::string &s, float volume=1.0f)
Plays a WAV or OGG file repeatedly.
Definition: sound_play.h:287
ros::Publisher pub_
Definition: sound_play.h:402
Sound waveSound(const std::string &s, float volume=1.0f)
Create a wave Sound.
Definition: sound_play.h:156
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
SoundClient()
Create a SoundClient with the default topic.
Definition: sound_play.h:131
Sound voiceSound(const std::string &s, float volume=1.0f)
Create a voice Sound.
Definition: sound_play.h:143
void stopWave(const std::string &s)
Stop playing a WAV or OGG file.
Definition: sound_play.h:258
void say(const std::string &s, const std::string &voice="voice_kal_diphone", float volume=1.0f)
Say a string.
Definition: sound_play.h:195
uint32_t getNumSubscribers() const
void setQuiet(bool state)
Turns warning messages on or off.
Definition: sound_play.h:360
void playWave(const std::string &s, float volume=1.0f)
Plays a WAV or OGG file.
Definition: sound_play.h:233
Class that publishes messages to the sound_play node.
Definition: sound_play.h:61
void init(ros::NodeHandle nh, const std::string &topic)
Definition: sound_play.h:366
bool ok() const
string voice
Definition: say.py:66
Sound(SoundClient *sc, int snd, const std::string &arg, const std::string arg2=std::string(), const float vol=1.0f)
Definition: sound_play.h:74
void stop()
Stop Sound playback.
Definition: sound_play.h:107
void stop(int sound)
Stop playing a built-in sound.
Definition: sound_play.h:338


sound_play
Author(s): Blaise Gassend
autogenerated on Fri Apr 9 2021 02:41:17