libsoundplay.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 #***********************************************************
4 #* Software License Agreement (BSD License)
5 #*
6 #* Copyright (c) 2009, Willow Garage, Inc.
7 #* All rights reserved.
8 #*
9 #* Redistribution and use in source and binary forms, with or without
10 #* modification, are permitted provided that the following conditions
11 #* are met:
12 #*
13 #* * Redistributions of source code must retain the above copyright
14 #* notice, this list of conditions and the following disclaimer.
15 #* * Redistributions in binary form must reproduce the above
16 #* copyright notice, this list of conditions and the following
17 #* disclaimer in the documentation and/or other materials provided
18 #* with the distribution.
19 #* * Neither the name of the Willow Garage nor the names of its
20 #* contributors may be used to endorse or promote products derived
21 #* from this software without specific prior written permission.
22 #*
23 #* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24 #* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25 #* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26 #* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27 #* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28 #* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29 #* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30 #* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31 #* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32 #* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33 #* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34 #* POSSIBILITY OF SUCH DAMAGE.
35 #***********************************************************
36 
37 # Author: Blaise Gassend
38 
39 import rospy
40 import roslib
41 import actionlib
42 import os, sys
43 from sound_play.msg import SoundRequest
44 from sound_play.msg import SoundRequestGoal
45 from sound_play.msg import SoundRequestAction
46 
47 ## \brief Class that publishes messages to the sound_play node.
48 
57 
58 class Sound(object):
59  def __init__(self, client, snd, arg, volume=1.0):
60  self.client = client
61  self.snd = snd
62  self.arg = arg
63  self.vol = volume
64 
65 ## \brief Play the Sound.
66 
68 
69  def play(self, **kwargs):
70  self.client.sendMsg(self.snd, SoundRequest.PLAY_ONCE, self.arg,
71  vol=self.vol, **kwargs)
72 
73 ## \brief Play the Sound repeatedly.
74 
77 
78  def repeat(self, **kwargs):
79  self.client.sendMsg(self.snd, SoundRequest.PLAY_START, self.arg,
80  vol=self.vol, **kwargs)
81 
82 ## \brief Stop Sound playback.
83 
85 
86  def stop(self):
87  self.client.sendMsg(self.snd, SoundRequest.PLAY_STOP, self.arg)
88 
89 ## This class is a helper class for communicating with the sound_play node
90 ## via the \ref sound_play.SoundRequest message. There is a one-to-one mapping
91 ## between methods and invocations of the \ref sound_play.SoundRequest message.
92 
93 class SoundClient(object):
94 
95  def __init__(self, blocking=False):
96  """
97 
98  The SoundClient can send SoundRequests in two modes: non-blocking mode
99  (by publishing a message to the soundplay_node directly) which will
100  return as soon as the sound request has been sent, or blocking mode (by
101  using the actionlib interface) which will wait until the sound has
102  finished playing completely.
103 
104  The blocking parameter here is the standard behavior, but can be
105  over-ridden. Each say/play/start/repeat method can take in an optional
106  `blocking=True|False` argument that will over-ride the class-wide
107  behavior. See soundclient_example.py for an example of this behavior.
108 
109  :param blocking: Used as the default behavior unless over-ridden,
110  (default = false)
111  """
112 
113  self._blocking = blocking
114 
115  # NOTE: only one of these will be used at once, but we need to create
116  # both the publisher and actionlib client here.
118  'sound_play', SoundRequestAction)
119  self.pub = rospy.Publisher('robotsound', SoundRequest, queue_size=5)
120 
121 ## \brief Create a voice Sound.
122 
126 
127  def voiceSound(self, s, volume=1.0):
128  return Sound(self, SoundRequest.SAY, s, volume=volume)
129 
130 ## \brief Create a wave Sound.
131 
136  def waveSound(self, sound, volume=1.0):
137  if sound[0] != "/":
138  rootdir = os.path.join(roslib.packages.get_pkg_dir('sound_play'),'sounds')
139  sound = rootdir + "/" + sound
140  return Sound(self, SoundRequest.PLAY_FILE, sound, volume=volume)
141 
142 ## \brief Create a builtin Sound.
143 
147 
148  def builtinSound(self, id, volume=1.0):
149  return Sound(self, id, "", volume)
150 
151 ## \brief Say a string
152 
157 
158  def say(self,text, voice='', volume=1.0, **kwargs):
159  self.sendMsg(SoundRequest.SAY, SoundRequest.PLAY_ONCE, text, voice,
160  volume, **kwargs)
161 
162 ## \brief Say a string repeatedly
163 
167 
168  def repeat(self,text, volume=1.0, **kwargs):
169  self.sendMsg(SoundRequest.SAY, SoundRequest.PLAY_START, text,
170  vol=volume, **kwargs)
171 
172 ## \brief Stop saying a string
173 
178 
179  def stopSaying(self,text):
180  self.sendMsg(SoundRequest.SAY, SoundRequest.PLAY_STOP, text)
181 
182 ## \brief Plays a WAV or OGG file
183 
189 
190  def playWave(self, sound, volume=1.0, **kwargs):
191  if sound[0] != "/":
192  rootdir = os.path.join(roslib.packages.get_pkg_dir('sound_play'),'sounds')
193  sound = rootdir + "/" + sound
194  self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_ONCE, sound,
195  vol=volume, **kwargs)
196 
197 ## \brief Plays a WAV or OGG file repeatedly
198 
203 
204  def startWave(self, sound, volume=1.0, **kwargs):
205  if sound[0] != "/":
206  rootdir = os.path.join(roslib.packages.get_pkg_dir('sound_play'),'sounds')
207  sound = rootdir + "/" + sound
208  self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_START, sound,
209  vol=volume, **kwargs)
210 
211 ## \brief Stop playing a WAV or OGG file
212 
217 
218  def stopWave(self,sound):
219  if sound[0] != "/":
220  rootdir = os.path.join(roslib.package.get_pkg_dir('sound_play'),'sounds')
221  sound = rootdir + "/" + sound
222  self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_STOP, sound)
223 
224 ## \brief Plays a WAV or OGG file
225 
232 
233  def playWaveFromPkg(self, package, sound, volume=1.0, **kwargs):
234  self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_ONCE, sound, package,
235  volume, **kwargs)
236 
237 ## \brief Plays a WAV or OGG file repeatedly
238 
244 
245  def startWaveFromPkg(self, package, sound, volume=1.0, **kwargs):
246  self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_START, sound,
247  package, volume, **kwargs)
248 
249 ## \brief Stop playing a WAV or OGG file
250 
257 
258  def stopWaveFromPkg(self,sound, package):
259  self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_STOP, sound, package)
260 
261 ## \brief Play a buildin sound
262 
267 
268  def play(self,sound, volume=1.0, **kwargs):
269  self.sendMsg(sound, SoundRequest.PLAY_ONCE, "", vol=volume, **kwargs)
270 
271 ## \brief Play a buildin sound repeatedly
272 
277 
278  def start(self,sound, volume=1.0, **kwargs):
279  self.sendMsg(sound, SoundRequest.PLAY_START, "", vol=volume, **kwargs)
280 
281 ## \brief Stop playing a built-in sound
282 
286 
287  def stop(self,sound):
288  self.sendMsg(sound, SoundRequest.PLAY_STOP, "")
289 
290 ## \brief Stop all currently playing sounds
291 
293 
294  def stopAll(self):
295  self.stop(SoundRequest.ALL)
296 
297  def sendMsg(self, snd, cmd, s, arg2="", vol=1.0, **kwargs):
298  """
299  Internal method that publishes the sound request, either directly as a
300  SoundRequest to the soundplay_node or through the actionlib interface
301  (which blocks until the sound has finished playing).
302 
303  The blocking behavior is nominally the class-wide setting unless it has
304  been explicitly specified in the play call.
305  """
306 
307  # Use the passed-in argument if it exists, otherwise fall back to the
308  # class-wide setting.
309  blocking = kwargs.get('blocking', self._blocking)
310 
311  msg = SoundRequest()
312  msg.sound = snd
313  # Threshold volume between 0 and 1.
314  msg.volume = max(0, min(1, vol))
315  msg.command = cmd
316  msg.arg = s
317  msg.arg2 = arg2
318 
319  rospy.logdebug('Sending sound request with volume = {}'
320  ' and blocking = {}'.format(msg.volume, blocking))
321 
322  # Defensive check for the existence of the correct communicator.
323  if not blocking and not self.pub:
324  rospy.logerr('Publisher for SoundRequest must exist')
325  return
326  if blocking and not self.actionclient:
327  rospy.logerr('Action client for SoundRequest does not exist.')
328  return
329 
330  if not blocking: # Publish message directly and return immediately
331  self.pub.publish(msg)
332  if self.pub.get_num_connections() < 1:
333  rospy.logwarn("Sound command issued, but no node is subscribed"
334  " to the topic. Perhaps you forgot to run"
335  " soundplay_node.py?")
336  else: # Block until result comes back.
337  assert self.actionclient, 'Actionclient must exist'
338  rospy.logdebug('Sending action client sound request [blocking]')
339  self.actionclient.wait_for_server()
340  goal = SoundRequestGoal()
341  goal.sound_request = msg
342  self.actionclient.send_goal(goal)
343  self.actionclient.wait_for_result()
344  rospy.logdebug('sound request response received')
345 
346  return
def start(self, sound, volume=1.0, kwargs)
Play a buildin sound repeatedly.
def repeat(self, kwargs)
Play the Sound repeatedly.
Definition: libsoundplay.py:78
def waveSound(self, sound, volume=1.0)
Create a wave Sound.
def say(self, text, voice='', volume=1.0, kwargs)
Say a string.
def startWave(self, sound, volume=1.0, kwargs)
Plays a WAV or OGG file repeatedly.
def stopWave(self, sound)
Stop playing a WAV or OGG file.
def stopWaveFromPkg(self, sound, package)
Stop playing a WAV or OGG file.
def __init__(self, client, snd, arg, volume=1.0)
Definition: libsoundplay.py:59
def startWaveFromPkg(self, package, sound, volume=1.0, kwargs)
Plays a WAV or OGG file repeatedly.
def stop(self)
Stop Sound playback.
Definition: libsoundplay.py:86
def sendMsg(self, snd, cmd, s, arg2="", vol=1.0, kwargs)
def voiceSound(self, s, volume=1.0)
Create a voice Sound.
def builtinSound(self, id, volume=1.0)
Create a builtin Sound.
def stopAll(self)
Stop all currently playing sounds.
def playWaveFromPkg(self, package, sound, volume=1.0, kwargs)
Plays a WAV or OGG file.
def play(self, kwargs)
Play the Sound.
Definition: libsoundplay.py:69
def playWave(self, sound, volume=1.0, kwargs)
Plays a WAV or OGG file.
def __init__(self, blocking=False)
Definition: libsoundplay.py:95
def stopSaying(self, text)
Stop saying a string.
This class is a helper class for communicating with the sound_play node via the sound_play.SoundRequest message.
Definition: libsoundplay.py:93
Class that publishes messages to the sound_play node.
Definition: libsoundplay.py:58


sound_play
Author(s): Blaise Gassend
autogenerated on Tue Mar 26 2019 02:30:56