43 from sound_play.msg
import SoundRequest
44 from sound_play.msg
import SoundRequestGoal
45 from sound_play.msg
import SoundRequestAction
59 def __init__(self, client, snd, arg, volume=1.0):
70 self.client.sendMsg(self.snd, SoundRequest.PLAY_ONCE, self.arg,
71 vol=self.vol, **kwargs)
79 self.client.sendMsg(self.snd, SoundRequest.PLAY_START, self.arg,
80 vol=self.vol, **kwargs)
87 self.client.sendMsg(self.snd, SoundRequest.PLAY_STOP, self.arg)
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. 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. 109 :param blocking: Used as the default behavior unless over-ridden, 118 'sound_play', SoundRequestAction)
119 self.
pub = rospy.Publisher(
'robotsound', SoundRequest, queue_size=5)
128 return Sound(self, SoundRequest.SAY, s, volume=volume)
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)
149 return Sound(self, id,
"", volume)
158 def say(self,text, voice='', volume=1.0, **kwargs):
159 self.sendMsg(SoundRequest.SAY, SoundRequest.PLAY_ONCE, text, voice,
168 def repeat(self,text, volume=1.0, **kwargs):
169 self.sendMsg(SoundRequest.SAY, SoundRequest.PLAY_START, text,
170 vol=volume, **kwargs)
180 self.sendMsg(SoundRequest.SAY, SoundRequest.PLAY_STOP, text)
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)
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)
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)
234 self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_ONCE, sound, package,
246 self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_START, sound,
247 package, volume, **kwargs)
259 self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_STOP, sound, package)
268 def play(self,sound, volume=1.0, **kwargs):
269 self.sendMsg(sound, SoundRequest.PLAY_ONCE,
"", vol=volume, **kwargs)
278 def start(self,sound, volume=1.0, **kwargs):
279 self.sendMsg(sound, SoundRequest.PLAY_START,
"", vol=volume, **kwargs)
288 self.sendMsg(sound, SoundRequest.PLAY_STOP,
"")
295 self.stop(SoundRequest.ALL)
297 def sendMsg(self, snd, cmd, s, arg2="", vol=1.0, **kwargs):
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). 303 The blocking behavior is nominally the class-wide setting unless it has 304 been explicitly specified in the play call. 309 blocking = kwargs.get(
'blocking', self._blocking)
314 msg.volume = max(0, min(1, vol))
319 rospy.logdebug(
'Sending sound request with volume = {}' 320 ' and blocking = {}'.format(msg.volume, blocking))
323 if not blocking
and not self.pub:
324 rospy.logerr(
'Publisher for SoundRequest must exist')
326 if blocking
and not self.actionclient:
327 rospy.logerr(
'Action client for SoundRequest does not exist.')
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?")
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')
def start(self, sound, volume=1.0, kwargs)
Play a buildin sound repeatedly.
def repeat(self, kwargs)
Play the Sound repeatedly.
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)
def startWaveFromPkg(self, package, sound, volume=1.0, kwargs)
Plays a WAV or OGG file repeatedly.
def stop(self)
Stop Sound playback.
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.
def playWave(self, sound, volume=1.0, kwargs)
Plays a WAV or OGG file.
def __init__(self, blocking=False)
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.
Class that publishes messages to the sound_play node.