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 os, sys
00042 from sound_play.msg import SoundRequest
00043 
00044 ## \brief Class that publishes messages to the sound_play node.
00045 ##
00046 ## This class is a helper class for communicating with the sound_play node
00047 ## via the \ref sound_play.SoundRequest message. It has two ways of being used:
00048 ##
00049 ## - It can create Sound classes that represent a particular sound which
00050 ##   can be played, repeated or stopped.
00051 ##
00052 ## - It provides methods for each way in which the sound_play.SoundRequest
00053 ##   message can be invoked.
00054 
00055 class Sound:
00056     def __init__(self, client, snd, arg):
00057         self.client = client
00058         self.snd = snd
00059         self.arg = arg
00060     
00061 ## \brief Play the Sound.
00062 ## 
00063 ## This method causes the Sound to be played once.
00064 
00065     def play(self):
00066         self.client.sendMsg(self.snd, SoundRequest.PLAY_ONCE, self.arg)
00067 
00068 ## \brief Play the Sound repeatedly.
00069 ##
00070 ## This method causes the Sound to be played repeatedly until stop() is
00071 ## called.
00072     
00073     def repeat(self):
00074        self.client.sendMsg(self.snd, SoundRequest.PLAY_START, self.arg)
00075 
00076 ## \brief Stop Sound playback.
00077 ##
00078 ## This method causes the Sound to stop playing.
00079 
00080     def stop(self):
00081         self.client.sendMsg(self.snd, SoundRequest.PLAY_STOP, self.arg)
00082 
00083 ## This class is a helper class for communicating with the sound_play node
00084 ## via the \ref sound_play.SoundRequest message. There is a one-to-one mapping
00085 ## between methods and invocations of the \ref sound_play.SoundRequest message.
00086 
00087 class SoundClient:
00088     def __init__(self):
00089         self.pub = rospy.Publisher('robotsound', SoundRequest, queue_size=5)
00090 
00091 ## \brief Create a voice Sound.
00092 ##
00093 ## Creates a Sound corresponding to saying the indicated text.
00094 ##
00095 ## \param s Text to say
00096  
00097     def voiceSound(self, s):
00098         return Sound(self, SoundRequest.SAY, s)
00099 
00100 ## \brief Create a wave Sound.
00101 ##
00102 ## Creates a Sound corresponding to indicated file.
00103 ##
00104 ## \param s File to play. Should be an absolute path that exists on the
00105 ## machine running the sound_play node.
00106     def waveSound(self, sound):
00107         if sound[0] != "/":
00108           rootdir = os.path.join(roslib.packages.get_pkg_dir('sound_play'),'sounds')
00109           sound = rootdir + "/" + sound
00110         return Sound(self, SoundRequest.PLAY_FILE, sound)
00111     
00112 ## \brief Create a builtin Sound.
00113 ##
00114 ## Creates a Sound corresponding to indicated builtin wave.
00115 ##
00116 ## \param id Identifier of the sound to play.
00117 
00118     def builtinSound(self, id):
00119         return Sound(self, id, "")
00120 
00121 ## \brief Say a string
00122 ## 
00123 ## Send a string to be said by the sound_node. The vocalization can be
00124 ## stopped using stopSaying or stopAll.
00125 ## 
00126 ## \param text String to say
00127 
00128     def say(self,text, voice=''):
00129         self.sendMsg(SoundRequest.SAY, SoundRequest.PLAY_ONCE, text, voice)
00130 
00131 ## \brief Say a string repeatedly
00132 ## 
00133 ## The string is said repeatedly until stopSaying or stopAll is used.
00134 ## 
00135 ## \param text String to say repeatedly
00136 
00137     def repeat(self,text):
00138         self.sendMsg(SoundRequest.SAY, SoundRequest.PLAY_START, text)
00139 
00140 ## \brief Stop saying a string
00141 ## 
00142 ## Stops saying a string that was previously started by say or repeat. The
00143 ## argument indicates which string to stop saying.
00144 ## 
00145 ## \param text Same string as in the say or repeat command
00146 
00147     def stopSaying(self,text):
00148         self.sendMsg(SoundRequest.SAY, SoundRequest.PLAY_STOP, text)
00149     
00150 ## \brief Plays a WAV or OGG file
00151 ## 
00152 ## Plays a WAV or OGG file once. The playback can be stopped by stopWave or
00153 ## stopAll.
00154 ## 
00155 ## \param sound Filename of the WAV or OGG file. Must be an absolute path valid
00156 ## on the computer on which the sound_play node is running
00157 
00158     def playWave(self, sound):
00159         if sound[0] != "/":
00160           rootdir = os.path.join(roslib.packages.get_pkg_dir('sound_play'),'sounds')
00161           sound = rootdir + "/" + sound
00162         self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_ONCE, sound)
00163     
00164 ## \brief Plays a WAV or OGG file repeatedly
00165 ## 
00166 ## Plays a WAV or OGG file repeatedly until stopWave or stopAll is used.
00167 ## 
00168 ## \param sound Filename of the WAV or OGG file. Must be an absolute path valid
00169 ## on the computer on which the sound_play node is running.
00170 
00171     def startWave(self, sound):
00172         if sound[0] != "/":
00173           rootdir = os.path.join(roslib.packages.get_pkg_dir('sound_play'),'sounds')
00174           sound = rootdir + "/" + sound
00175         self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_START, sound)
00176 
00177 ##  \brief Stop playing a WAV or OGG file
00178 ## 
00179 ## Stops playing a file that was previously started by playWave or
00180 ## startWave.
00181 ## 
00182 ## \param sound Same string as in the playWave or startWave command
00183 
00184     def stopWave(self,sound):
00185         if sound[0] != "/":
00186           rootdir = os.path.join(roslib.package.get_pkg_dir('sound_play'),'sounds')
00187           sound = rootdir + "/" + sound
00188         self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_STOP, sound)
00189 
00190 ## \brief Plays a WAV or OGG file
00191 ## 
00192 ## Plays a WAV or OGG file once. The playback can be stopped by stopWaveFromPkg or
00193 ## stopAll.
00194 ## 
00195 ## \param package Package name containing the sound file.
00196 ## \param sound Filename of the WAV or OGG file. Must be an path relative to the package valid
00197 ## on the computer on which the sound_play node is running
00198 
00199     def playWaveFromPkg(self, package, sound):
00200         self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_ONCE, sound, package)
00201 
00202 ## \brief Plays a WAV or OGG file repeatedly
00203 ## 
00204 ## Plays a WAV or OGG file repeatedly until stopWaveFromPkg or stopAll is used.
00205 ## 
00206 ## \param package Package name containing the sound file.
00207 ## \param sound Filename of the WAV or OGG file. Must be an path relative to the package valid
00208 ## on the computer on which the sound_play node is running
00209 
00210     def startWaveFromPkg(self, package, sound):
00211         self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_START, sound, package)
00212 
00213 ##  \brief Stop playing a WAV or OGG file
00214 ## 
00215 ## Stops playing a file that was previously started by playWaveFromPkg or
00216 ## startWaveFromPkg.
00217 ## 
00218 ## \param package Package name containing the sound file.
00219 ## \param sound Filename of the WAV or OGG file. Must be an path relative to the package valid
00220 ## on the computer on which the sound_play node is running
00221 
00222     def stopWaveFromPkg(self,sound, package):
00223         self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_STOP, sound, package)
00224 
00225 ## \brief Play a buildin sound
00226 ##
00227 ## Starts playing one of the built-in sounds. built-ing sounds are documented
00228 ## in \ref SoundRequest.msg. Playback can be stopped by stopall.
00229 ##
00230 ## \param sound Identifier of the sound to play.
00231 
00232     def play(self,sound):
00233         self.sendMsg(sound, SoundRequest.PLAY_ONCE, "")
00234 
00235 ## \brief Play a buildin sound repeatedly
00236 ##
00237 ## Starts playing one of the built-in sounds repeatedly until stop or
00238 ## stopall is used. Built-in sounds are documented in \ref SoundRequest.msg.
00239 ##
00240 ## \param sound Identifier of the sound to play.
00241     
00242     def start(self,sound):
00243         self.sendMsg(sound, SoundRequest.PLAY_START, "")
00244 
00245 ## \brief Stop playing a built-in sound
00246 ##
00247 ## Stops playing a built-in sound started with play or start. 
00248 ##
00249 ## \param sound Same sound that was used to start playback
00250     
00251     def stop(self,sound):
00252         self.sendMsg(sound, SoundRequest.PLAY_STOP, "")
00253 
00254 ## \brief Stop all currently playing sounds
00255 ##
00256 ## This method stops all speech, wave file, and built-in sound playback.
00257   
00258     def stopAll(self):
00259         self.stop(SoundRequest.ALL)
00260 
00261     def sendMsg(self, snd, cmd, s, arg2=""):
00262         msg = SoundRequest()
00263         msg.sound = snd
00264         msg.command = cmd
00265         msg.arg = s
00266         msg.arg2 = arg2 
00267         self.pub.publish(msg)
00268         ## @todo this should be a warn once warns become visible on the console.
00269         if self.pub.get_num_connections() < 1:
00270             rospy.logerr("Sound command issued, but no node is subscribed to the topic. Perhaps you forgot to run soundplay_node.py");


sound_play
Author(s): Blaise Gassend
autogenerated on Wed Sep 2 2015 01:21:46