41 from actionlib_msgs.msg
import GoalStatusArray
42 from sound_play.msg
import SoundRequest
43 from sound_play.msg
import SoundRequestGoal
44 from sound_play.msg
import SoundRequestAction
58 def __init__(self, client, snd, arg, volume=1.0):
69 self.client.
sendMsg(self.snd, SoundRequest.PLAY_ONCE, self.arg,
70 vol=self.vol, **kwargs)
78 self.client.
sendMsg(self.snd, SoundRequest.PLAY_START, self.arg,
79 vol=self.vol, **kwargs)
86 self.client.
sendMsg(self.snd, SoundRequest.PLAY_STOP, self.arg)
94 def __init__(self, blocking=False, sound_action='sound_play', sound_topic='robotsound'):
97 The SoundClient can send SoundRequests in two modes: non-blocking mode
98 (by publishing a message to the soundplay_node directly) which will
99 return as soon as the sound request has been sent, or blocking mode (by
100 using the actionlib interface) which will wait until the sound has
101 finished playing completely.
103 The blocking parameter here is the standard behavior, but can be
104 over-ridden. Each say/play/start/repeat method can take in an optional
105 `blocking=True|False` argument that will over-ride the class-wide
106 behavior. See soundclient_example.py for an example of this behavior.
108 :param blocking: Used as the default behavior unless over-ridden,
111 :param sound_action: Namespace of actionlib to play sound. The actionlib interface is used
112 only if blocking parameter is True. (default='sound_play')
114 :param sound_topic: Topic name to play sound. The topic interface is used only if blocking
115 parameter is False. (default='robotsound')
124 sound_action, SoundRequestAction)
125 self.
pub = rospy.Publisher(sound_topic, SoundRequest, queue_size=5)
126 self.
sub = rospy.Subscriber(
127 '{}/status'.format(sound_action), GoalStatusArray, self._action_status_cb)
136 return Sound(self, SoundRequest.SAY, s, volume=volume)
146 rootdir = os.path.join(roslib.packages.get_pkg_dir(
'sound_play'),
'sounds')
147 sound = rootdir +
"/" + sound
148 return Sound(self, SoundRequest.PLAY_FILE, sound, volume=volume)
157 return Sound(self, id,
"", volume)
166 def say(self,text, voice='', volume=1.0, **kwargs):
167 self.sendMsg(SoundRequest.SAY, SoundRequest.PLAY_ONCE, text, voice,
176 def repeat(self,text, volume=1.0, **kwargs):
177 self.sendMsg(SoundRequest.SAY, SoundRequest.PLAY_START, text,
178 vol=volume, **kwargs)
188 self.sendMsg(SoundRequest.SAY, SoundRequest.PLAY_STOP, text)
200 rootdir = os.path.join(roslib.packages.get_pkg_dir(
'sound_play'),
'sounds')
201 sound = rootdir +
"/" + sound
202 self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_ONCE, sound,
203 vol=volume, **kwargs)
214 rootdir = os.path.join(roslib.packages.get_pkg_dir(
'sound_play'),
'sounds')
215 sound = rootdir +
"/" + sound
216 self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_START, sound,
217 vol=volume, **kwargs)
228 rootdir = os.path.join(roslib.package.get_pkg_dir(
'sound_play'),
'sounds')
229 sound = rootdir +
"/" + sound
230 self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_STOP, sound)
242 self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_ONCE, sound, package,
254 self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_START, sound,
255 package, volume, **kwargs)
267 self.sendMsg(SoundRequest.PLAY_FILE, SoundRequest.PLAY_STOP, sound, package)
276 def play(self,sound, volume=1.0, **kwargs):
277 self.sendMsg(sound, SoundRequest.PLAY_ONCE,
"", vol=volume, **kwargs)
286 def start(self,sound, volume=1.0, **kwargs):
287 self.sendMsg(sound, SoundRequest.PLAY_START,
"", vol=volume, **kwargs)
296 self.sendMsg(sound, SoundRequest.PLAY_STOP,
"")
303 self.stop(SoundRequest.ALL)
306 self, snd, cmd, s, arg2="", vol=1.0, replace=True,
307 server_timeout=None, result_timeout=None,
311 Internal method that publishes the sound request, either directly as a
312 SoundRequest to the soundplay_node or through the actionlib interface
313 (which blocks until the sound has finished playing).
315 The blocking behavior is nominally the class-wide setting unless it has
316 been explicitly specified in the play call.
321 blocking = kwargs.get(
'blocking', self._blocking)
326 msg.volume = max(0, min(1, vol))
331 rospy.logdebug(
'Sending sound request with volume = {}'
332 ' and blocking = {}'.format(msg.volume, blocking))
335 if not blocking
and not self.pub:
336 rospy.logerr(
'Publisher for SoundRequest must exist')
338 if blocking
and not self.actionclient:
339 rospy.logerr(
'Action client for SoundRequest does not exist.')
343 self.pub.publish(msg)
344 if self.pub.get_num_connections() < 1:
345 rospy.logwarn(
"Sound command issued, but no node is subscribed"
346 " to the topic. Perhaps you forgot to run"
347 " soundplay_node.py?")
349 assert self.actionclient,
'Actionclient must exist'
350 rospy.logdebug(
'Sending action client sound request [blocking]')
352 if server_timeout
is None or server_timeout > rospy.Duration(0):
353 if server_timeout
is None:
354 server_timeout = rospy.Duration()
355 if not self.actionclient.wait_for_server(timeout=server_timeout):
358 goal = SoundRequestGoal()
359 goal.sound_request = msg
360 while not replace
and self._playing:
362 self.actionclient.send_goal(goal)
363 if result_timeout
is None or result_timeout > rospy.Duration(0):
364 if result_timeout
is None:
365 result_timeout = rospy.Duration()
366 if self.actionclient.wait_for_result(timeout=result_timeout):
367 rospy.logdebug(
'sound request response received')
371 if 1
in [s.status
for s
in msg.status_list]:
374 self._playing =
False