00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
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
00048
00049
00050
00051
00052
00053
00054
00055
00056
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
00065
00066
00067
00068 def play(self, **kwargs):
00069 self.client.sendMsg(self.snd, SoundRequest.PLAY_ONCE, self.arg,
00070 **kwargs)
00071
00072
00073
00074
00075
00076
00077 def repeat(self, **kwargs):
00078 self.client.sendMsg(self.snd, SoundRequest.PLAY_START, self.arg,
00079 **kwargs)
00080
00081
00082
00083
00084
00085 def stop(self):
00086 self.client.sendMsg(self.snd, SoundRequest.PLAY_STOP, self.arg)
00087
00088
00089
00090
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
00115
00116 self.actionclient = actionlib.SimpleActionClient(
00117 'sound_play', SoundRequestAction)
00118 self.pub = rospy.Publisher('robotsound', SoundRequest, queue_size=5)
00119
00120
00121
00122
00123
00124
00125
00126 def voiceSound(self, s):
00127 return Sound(self, SoundRequest.SAY, s)
00128
00129
00130
00131
00132
00133
00134
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
00142
00143
00144
00145
00146
00147 def builtinSound(self, id):
00148 return Sound(self, id, "")
00149
00150
00151
00152
00153
00154
00155
00156
00157 def say(self,text, voice='', **kwargs):
00158 self.sendMsg(SoundRequest.SAY, SoundRequest.PLAY_ONCE, text, voice,
00159 **kwargs)
00160
00161
00162
00163
00164
00165
00166
00167 def repeat(self,text, **kwargs):
00168 self.sendMsg(SoundRequest.SAY, SoundRequest.PLAY_START, text,
00169 **kwargs)
00170
00171
00172
00173
00174
00175
00176
00177
00178 def stopSaying(self,text):
00179 self.sendMsg(SoundRequest.SAY, SoundRequest.PLAY_STOP, text)
00180
00181
00182
00183
00184
00185
00186
00187
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
00197
00198
00199
00200
00201
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
00211
00212
00213
00214
00215
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
00224
00225
00226
00227
00228
00229
00230
00231
00232 def playWaveFromPkg(self, package, sound, **kwargs):
00233 self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_ONCE, sound, package,
00234 **kwargs)
00235
00236
00237
00238
00239
00240
00241
00242
00243
00244 def startWaveFromPkg(self, package, sound, **kwargs):
00245 self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_START, sound,
00246 package, **kwargs)
00247
00248
00249
00250
00251
00252
00253
00254
00255
00256
00257 def stopWaveFromPkg(self,sound, package):
00258 self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_STOP, sound, package)
00259
00260
00261
00262
00263
00264
00265
00266
00267 def play(self,sound, **kwargs):
00268 self.sendMsg(sound, SoundRequest.PLAY_ONCE, "", **kwargs)
00269
00270
00271
00272
00273
00274
00275
00276
00277 def start(self,sound, **kwargs):
00278 self.sendMsg(sound, SoundRequest.PLAY_START, "", **kwargs)
00279
00280
00281
00282
00283
00284
00285
00286 def stop(self,sound):
00287 self.sendMsg(sound, SoundRequest.PLAY_STOP, "")
00288
00289
00290
00291
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
00307
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
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:
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:
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