libsoundplay.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 #***********************************************************
00004 #* Software License Agreement (BSD License)
00005 #*
00006 #*  Copyright (c) 2009, Willow Garage, Inc.
00007 #*  All rights reserved.
00008 #*
00009 #*  Redistribution and use in source and binary forms, with or without
00010 #*  modification, are permitted provided that the following conditions
00011 #*  are met:
00012 #*
00013 #*   * Redistributions of source code must retain the above copyright
00014 #*     notice, this list of conditions and the following disclaimer.
00015 #*   * Redistributions in binary form must reproduce the above
00016 #*     copyright notice, this list of conditions and the following
00017 #*     disclaimer in the documentation and/or other materials provided
00018 #*     with the distribution.
00019 #*   * Neither the name of the Willow Garage nor the names of its
00020 #*     contributors may be used to endorse or promote products derived
00021 #*     from this software without specific prior written permission.
00022 #*
00023 #*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024 #*  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025 #*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026 #*  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027 #*  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028 #*  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029 #*  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030 #*  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031 #*  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032 #*  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033 #*  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034 #*  POSSIBILITY OF SUCH DAMAGE.
00035 #***********************************************************
00036 
00037 # Author: Blaise Gassend
00038 
00039 import rospy
00040 import roslib
00041 import actionlib
00042 import os, sys
00043 from sound_play.msg import SoundRequest
00044 from sound_play.msg import SoundRequestGoal
00045 from sound_play.msg import SoundRequestAction
00046 
00047 ## \brief Class that publishes messages to the sound_play node.
00048 ##
00049 ## This class is a helper class for communicating with the sound_play node
00050 ## via the \ref sound_play.SoundRequest message. It has two ways of being used:
00051 ##
00052 ## - It can create Sound classes that represent a particular sound which
00053 ##   can be played, repeated or stopped.
00054 ##
00055 ## - It provides methods for each way in which the sound_play.SoundRequest
00056 ##   message can be invoked.
00057 
00058 class Sound(object):
00059     def __init__(self, client, snd, arg):
00060         self.client = client
00061         self.snd = snd
00062         self.arg = arg
00063 
00064 ## \brief Play the Sound.
00065 ##
00066 ## This method causes the Sound to be played once.
00067 
00068     def play(self, **kwargs):
00069         self.client.sendMsg(self.snd, SoundRequest.PLAY_ONCE, self.arg,
00070                             **kwargs)
00071 
00072 ## \brief Play the Sound repeatedly.
00073 ##
00074 ## This method causes the Sound to be played repeatedly until stop() is
00075 ## called.
00076 
00077     def repeat(self, **kwargs):
00078        self.client.sendMsg(self.snd, SoundRequest.PLAY_START, self.arg,
00079                            **kwargs)
00080 
00081 ## \brief Stop Sound playback.
00082 ##
00083 ## This method causes the Sound to stop playing.
00084 
00085     def stop(self):
00086         self.client.sendMsg(self.snd, SoundRequest.PLAY_STOP, self.arg)
00087 
00088 ## This class is a helper class for communicating with the sound_play node
00089 ## via the \ref sound_play.SoundRequest message. There is a one-to-one mapping
00090 ## between methods and invocations of the \ref sound_play.SoundRequest message.
00091 
00092 class SoundClient(object):
00093 
00094     def __init__(self, blocking=False):
00095         """
00096 
00097         The SoundClient can send SoundRequests in two modes: non-blocking mode
00098         (by publishing a message to the soundplay_node directly) which will
00099         return as soon as the sound request has been sent, or blocking mode (by
00100         using the actionlib interface) which will wait until the sound has
00101         finished playing completely.
00102 
00103         The blocking parameter here is the standard behavior, but can be
00104         over-ridden.  Each say/play/start/repeat method can take in an optional
00105         `blocking=True|False` argument that will over-ride the class-wide
00106         behavior. See soundclient_example.py for an example of this behavior.
00107 
00108         :param blocking: Used as the default behavior unless over-ridden,
00109         (default = false)
00110         """
00111 
00112         self._blocking = blocking
00113 
00114         # NOTE: only one of these will be used at once, but we need to create
00115         # both the publisher and actionlib client here.
00116         self.actionclient = actionlib.SimpleActionClient(
00117             'sound_play', SoundRequestAction)
00118         self.pub = rospy.Publisher('robotsound', SoundRequest, queue_size=5)
00119 
00120 ## \brief Create a voice Sound.
00121 ##
00122 ## Creates a Sound corresponding to saying the indicated text.
00123 ##
00124 ## \param s Text to say
00125 
00126     def voiceSound(self, s):
00127         return Sound(self, SoundRequest.SAY, s)
00128 
00129 ## \brief Create a wave Sound.
00130 ##
00131 ## Creates a Sound corresponding to indicated file.
00132 ##
00133 ## \param s File to play. Should be an absolute path that exists on the
00134 ## machine running the sound_play node.
00135     def waveSound(self, sound):
00136         if sound[0] != "/":
00137           rootdir = os.path.join(roslib.packages.get_pkg_dir('sound_play'),'sounds')
00138           sound = rootdir + "/" + sound
00139         return Sound(self, SoundRequest.PLAY_FILE, sound)
00140 
00141 ## \brief Create a builtin Sound.
00142 ##
00143 ## Creates a Sound corresponding to indicated builtin wave.
00144 ##
00145 ## \param id Identifier of the sound to play.
00146 
00147     def builtinSound(self, id):
00148         return Sound(self, id, "")
00149 
00150 ## \brief Say a string
00151 ##
00152 ## Send a string to be said by the sound_node. The vocalization can be
00153 ## stopped using stopSaying or stopAll.
00154 ##
00155 ## \param text String to say
00156 
00157     def say(self,text, voice='', **kwargs):
00158         self.sendMsg(SoundRequest.SAY, SoundRequest.PLAY_ONCE, text, voice,
00159                      **kwargs)
00160 
00161 ## \brief Say a string repeatedly
00162 ##
00163 ## The string is said repeatedly until stopSaying or stopAll is used.
00164 ##
00165 ## \param text String to say repeatedly
00166 
00167     def repeat(self,text, **kwargs):
00168         self.sendMsg(SoundRequest.SAY, SoundRequest.PLAY_START, text,
00169                      **kwargs)
00170 
00171 ## \brief Stop saying a string
00172 ##
00173 ## Stops saying a string that was previously started by say or repeat. The
00174 ## argument indicates which string to stop saying.
00175 ##
00176 ## \param text Same string as in the say or repeat command
00177 
00178     def stopSaying(self,text):
00179         self.sendMsg(SoundRequest.SAY, SoundRequest.PLAY_STOP, text)
00180 
00181 ## \brief Plays a WAV or OGG file
00182 ##
00183 ## Plays a WAV or OGG file once. The playback can be stopped by stopWave or
00184 ## stopAll.
00185 ##
00186 ## \param sound Filename of the WAV or OGG file. Must be an absolute path valid
00187 ## on the computer on which the sound_play node is running
00188 
00189     def playWave(self, sound, **kwargs):
00190         if sound[0] != "/":
00191           rootdir = os.path.join(roslib.packages.get_pkg_dir('sound_play'),'sounds')
00192           sound = rootdir + "/" + sound
00193         self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_ONCE, sound,
00194                      **kwargs)
00195 
00196 ## \brief Plays a WAV or OGG file repeatedly
00197 ##
00198 ## Plays a WAV or OGG file repeatedly until stopWave or stopAll is used.
00199 ##
00200 ## \param sound Filename of the WAV or OGG file. Must be an absolute path valid
00201 ## on the computer on which the sound_play node is running.
00202 
00203     def startWave(self, sound, **kwargs):
00204         if sound[0] != "/":
00205           rootdir = os.path.join(roslib.packages.get_pkg_dir('sound_play'),'sounds')
00206           sound = rootdir + "/" + sound
00207         self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_START, sound,
00208                      **kwargs)
00209 
00210 ##  \brief Stop playing a WAV or OGG file
00211 ##
00212 ## Stops playing a file that was previously started by playWave or
00213 ## startWave.
00214 ##
00215 ## \param sound Same string as in the playWave or startWave command
00216 
00217     def stopWave(self,sound):
00218         if sound[0] != "/":
00219           rootdir = os.path.join(roslib.package.get_pkg_dir('sound_play'),'sounds')
00220           sound = rootdir + "/" + sound
00221         self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_STOP, sound)
00222 
00223 ## \brief Plays a WAV or OGG file
00224 ##
00225 ## Plays a WAV or OGG file once. The playback can be stopped by stopWaveFromPkg or
00226 ## stopAll.
00227 ##
00228 ## \param package Package name containing the sound file.
00229 ## \param sound Filename of the WAV or OGG file. Must be an path relative to the package valid
00230 ## on the computer on which the sound_play node is running
00231 
00232     def playWaveFromPkg(self, package, sound, **kwargs):
00233         self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_ONCE, sound, package,
00234                      **kwargs)
00235 
00236 ## \brief Plays a WAV or OGG file repeatedly
00237 ##
00238 ## Plays a WAV or OGG file repeatedly until stopWaveFromPkg or stopAll is used.
00239 ##
00240 ## \param package Package name containing the sound file.
00241 ## \param sound Filename of the WAV or OGG file. Must be an path relative to the package valid
00242 ## on the computer on which the sound_play node is running
00243 
00244     def startWaveFromPkg(self, package, sound, **kwargs):
00245         self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_START, sound,
00246                      package, **kwargs)
00247 
00248 ##  \brief Stop playing a WAV or OGG file
00249 ##
00250 ## Stops playing a file that was previously started by playWaveFromPkg or
00251 ## startWaveFromPkg.
00252 ##
00253 ## \param package Package name containing the sound file.
00254 ## \param sound Filename of the WAV or OGG file. Must be an path relative to the package valid
00255 ## on the computer on which the sound_play node is running
00256 
00257     def stopWaveFromPkg(self,sound, package):
00258         self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_STOP, sound, package)
00259 
00260 ## \brief Play a buildin sound
00261 ##
00262 ## Starts playing one of the built-in sounds. built-ing sounds are documented
00263 ## in \ref SoundRequest.msg. Playback can be stopped by stopall.
00264 ##
00265 ## \param sound Identifier of the sound to play.
00266 
00267     def play(self,sound, **kwargs):
00268         self.sendMsg(sound, SoundRequest.PLAY_ONCE, "", **kwargs)
00269 
00270 ## \brief Play a buildin sound repeatedly
00271 ##
00272 ## Starts playing one of the built-in sounds repeatedly until stop or
00273 ## stopall is used. Built-in sounds are documented in \ref SoundRequest.msg.
00274 ##
00275 ## \param sound Identifier of the sound to play.
00276 
00277     def start(self,sound, **kwargs):
00278         self.sendMsg(sound, SoundRequest.PLAY_START, "", **kwargs)
00279 
00280 ## \brief Stop playing a built-in sound
00281 ##
00282 ## Stops playing a built-in sound started with play or start.
00283 ##
00284 ## \param sound Same sound that was used to start playback
00285 
00286     def stop(self,sound):
00287         self.sendMsg(sound, SoundRequest.PLAY_STOP, "")
00288 
00289 ## \brief Stop all currently playing sounds
00290 ##
00291 ## This method stops all speech, wave file, and built-in sound playback.
00292 
00293     def stopAll(self):
00294         self.stop(SoundRequest.ALL)
00295 
00296     def sendMsg(self, snd, cmd, s, arg2="", **kwargs):
00297         """
00298         Internal method that publishes the sound request, either directly as a
00299         SoundRequest to the soundplay_node or through the actionlib interface
00300         (which blocks until the sound has finished playing).
00301 
00302         The blocking behavior is nominally the class-wide setting unless it has
00303         been explicitly specified in the play call.
00304         """
00305 
00306         # Use the passed-in argument if it exists, otherwise fall back to the
00307         # class-wide setting.
00308         blocking = kwargs.get('blocking', self._blocking)
00309 
00310         msg = SoundRequest()
00311         msg.sound = snd
00312         msg.command = cmd
00313         msg.arg = s
00314         msg.arg2 = arg2
00315 
00316         rospy.logdebug('Sending sound request with'
00317                        ' blocking = {}'.format(blocking))
00318 
00319         # Defensive check for the existence of the correct communicator.
00320         if not blocking and not self.pub:
00321             rospy.logerr('Publisher for SoundRequest must exist')
00322             return
00323         if blocking and not self.actionclient:
00324             rospy.logerr('Action client for SoundRequest does not exist.')
00325             return
00326 
00327         if not blocking:  # Publish message directly and return immediately
00328             self.pub.publish(msg)
00329             if self.pub.get_num_connections() < 1:
00330                 rospy.logwarn("Sound command issued, but no node is subscribed"
00331                               " to the topic. Perhaps you forgot to run"
00332                               " soundplay_node.py?")
00333         else:  # Block until result comes back.
00334             assert self.actionclient, 'Actionclient must exist'
00335             rospy.logdebug('Sending action client sound request [blocking]')
00336             self.actionclient.wait_for_server()
00337             goal = SoundRequestGoal()
00338             goal.sound_request = msg
00339             self.actionclient.send_goal(goal)
00340             self.actionclient.wait_for_result()
00341             rospy.logdebug('sound request response received')
00342 
00343         return


sound_play
Author(s): Blaise Gassend
autogenerated on Mon Sep 26 2016 03:31:16