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


sound_play
Author(s): Blaise Gassend, Austin Hendrix/ahendrix@willowgarage.com
autogenerated on Thu Aug 29 2013 00:50:45