41 from sound_play.msg
import SoundRequest
42 from sound_play.msg
import SoundRequestGoal
43 from sound_play.msg
import SoundRequestAction
57 def __init__(self, client, snd, arg, volume=1.0):
68 self.client.sendMsg(self.snd, SoundRequest.PLAY_ONCE, self.arg,
69 vol=self.vol, **kwargs)
77 self.client.sendMsg(self.snd, SoundRequest.PLAY_START, self.arg,
78 vol=self.vol, **kwargs)
85 self.client.sendMsg(self.snd, SoundRequest.PLAY_STOP, self.arg)
93 def __init__(self, blocking=False, sound_action='sound_play', sound_topic='robotsound'):
96 The SoundClient can send SoundRequests in two modes: non-blocking mode 97 (by publishing a message to the soundplay_node directly) which will 98 return as soon as the sound request has been sent, or blocking mode (by 99 using the actionlib interface) which will wait until the sound has 100 finished playing completely. 102 The blocking parameter here is the standard behavior, but can be 103 over-ridden. Each say/play/start/repeat method can take in an optional 104 `blocking=True|False` argument that will over-ride the class-wide 105 behavior. See soundclient_example.py for an example of this behavior. 107 :param blocking: Used as the default behavior unless over-ridden, 110 :param sound_action: Namespace of actionlib to play sound. The actionlib interface is used 111 only if blocking parameter is True. (default='sound_play') 113 :param sound_topic: Topic name to play sound. The topic interface is used only if blocking 114 parameter is False. (default='robotsound') 122 sound_action, SoundRequestAction)
123 self.
pub = rospy.Publisher(sound_topic, SoundRequest, queue_size=5)
132 return Sound(self, SoundRequest.SAY, s, volume=volume)
142 rootdir = os.path.join(roslib.packages.get_pkg_dir(
'sound_play'),
'sounds')
143 sound = rootdir +
"/" + sound
144 return Sound(self, SoundRequest.PLAY_FILE, sound, volume=volume)
153 return Sound(self, id,
"", volume)
162 def say(self,text, voice='', volume=1.0, **kwargs):
163 self.sendMsg(SoundRequest.SAY, SoundRequest.PLAY_ONCE, text, voice,
172 def repeat(self,text, volume=1.0, **kwargs):
173 self.sendMsg(SoundRequest.SAY, SoundRequest.PLAY_START, text,
174 vol=volume, **kwargs)
184 self.sendMsg(SoundRequest.SAY, SoundRequest.PLAY_STOP, text)
196 rootdir = os.path.join(roslib.packages.get_pkg_dir(
'sound_play'),
'sounds')
197 sound = rootdir +
"/" + sound
198 self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_ONCE, sound,
199 vol=volume, **kwargs)
210 rootdir = os.path.join(roslib.packages.get_pkg_dir(
'sound_play'),
'sounds')
211 sound = rootdir +
"/" + sound
212 self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_START, sound,
213 vol=volume, **kwargs)
224 rootdir = os.path.join(roslib.package.get_pkg_dir(
'sound_play'),
'sounds')
225 sound = rootdir +
"/" + sound
226 self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_STOP, sound)
238 self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_ONCE, sound, package,
250 self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_START, sound,
251 package, volume, **kwargs)
263 self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_STOP, sound, package)
272 def play(self,sound, volume=1.0, **kwargs):
273 self.sendMsg(sound, SoundRequest.PLAY_ONCE,
"", vol=volume, **kwargs)
282 def start(self,sound, volume=1.0, **kwargs):
283 self.sendMsg(sound, SoundRequest.PLAY_START,
"", vol=volume, **kwargs)
292 self.sendMsg(sound, SoundRequest.PLAY_STOP,
"")
299 self.stop(SoundRequest.ALL)
301 def sendMsg(self, snd, cmd, s, arg2="", vol=1.0, **kwargs):
303 Internal method that publishes the sound request, either directly as a 304 SoundRequest to the soundplay_node or through the actionlib interface 305 (which blocks until the sound has finished playing). 307 The blocking behavior is nominally the class-wide setting unless it has 308 been explicitly specified in the play call. 313 blocking = kwargs.get(
'blocking', self._blocking)
318 msg.volume = max(0, min(1, vol))
323 rospy.logdebug(
'Sending sound request with volume = {}' 324 ' and blocking = {}'.format(msg.volume, blocking))
327 if not blocking
and not self.pub:
328 rospy.logerr(
'Publisher for SoundRequest must exist')
330 if blocking
and not self.actionclient:
331 rospy.logerr(
'Action client for SoundRequest does not exist.')
335 self.pub.publish(msg)
336 if self.pub.get_num_connections() < 1:
337 rospy.logwarn(
"Sound command issued, but no node is subscribed" 338 " to the topic. Perhaps you forgot to run" 339 " soundplay_node.py?")
341 assert self.actionclient,
'Actionclient must exist' 342 rospy.logdebug(
'Sending action client sound request [blocking]')
343 self.actionclient.wait_for_server()
344 goal = SoundRequestGoal()
345 goal.sound_request = msg
346 self.actionclient.send_goal(goal)
347 self.actionclient.wait_for_result()
348 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 __init__(self, blocking=False, sound_action='sound_play', sound_topic='robotsound')
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 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.