48 from diagnostic_msgs.msg
import DiagnosticStatus, KeyValue, DiagnosticArray
49 from sound_play.msg
import SoundRequest, SoundRequestAction, SoundRequestResult, SoundRequestFeedback
79 def __init__(self, file, device, volume = 1.0):
80 self.
lock = threading.RLock()
90 elif os.path.isfile(file):
91 uri =
"file://" + os.path.abspath(file)
93 rospy.logerr(
'Error: URI is invalid: %s'%file)
146 rospy.logdebug(
"Playing %s"%self.
uri)
158 if cmd == SoundRequest.PLAY_STOP:
160 elif cmd == SoundRequest.PLAY_ONCE:
162 elif cmd == SoundRequest.PLAY_START:
173 except Exception
as e:
179 if position != duration:
189 _feedback = SoundRequestFeedback()
190 _result = SoundRequestResult()
193 for sound
in dict.values():
202 if data.sound == SoundRequest.PLAY_FILE:
205 rospy.logdebug(
'command for uncached wave: "%s"'%data.arg)
209 rospy.logerr(
'Error setting up to play "%s". Does this file exist on the machine on which sound_play is running?'%data.arg)
212 rospy.logdebug(
'command for cached wave: "%s"'%data.arg)
215 absfilename = os.path.join(roslib.packages.get_pkg_dir(data.arg2), data.arg)
217 rospy.logdebug(
'command for uncached wave: "%s"'%absfilename)
221 rospy.logerr(
'Error setting up to play "%s" from package "%s". Does this file exist on the machine on which sound_play is running?'%(data.arg, data.arg2))
224 rospy.logdebug(
'command for cached wave: "%s"'%absfilename)
226 elif data.sound == SoundRequest.SAY:
228 rospy.logdebug(
'command for uncached text: "%s"' % data.arg)
229 txtfile = tempfile.NamedTemporaryFile(prefix=
'sound_play', suffix=
'.txt')
230 (wavfile,wavfilename) = tempfile.mkstemp(prefix=
'sound_play', suffix=
'.wav')
231 txtfilename=txtfile.name
236 if sys.version_info.major >= 3
and type(data.arg)
is str:
237 data.arg = data.arg.encode()
238 txtfile.write(data.arg)
240 rospy.loginfo(
"text2wave -eval '("+voice+
")' "+txtfilename+
" -o "+wavfilename)
242 os.system("text2wave -eval '("+voice+")' "+txtfilename+" -o "+wavfilename)
244 if os.stat(wavfilename).st_size == 0:
245 raise OSError # So we hit the same catch block
247 rospy.logerr("text2wave -eval '("+voice+")' "+txtfilename+" -o "+wavfilename)
248 rospy.logerr('Sound synthesis failed. Is festival installed? Is a festival voice installed? Try running "rosdep satisfy sound_play|sh". Refer to http://wiki.ros.org/sound_play/Troubleshooting')
255 rospy.logdebug(
'command for cached text: "%s"'%data.arg)
258 rospy.logdebug(
'command for builtin wave: %i'%data.sound)
263 if sound.staleness != 0
and data.command != SoundRequest.PLAY_STOP:
265 rospy.logdebug(
"activating %i %s"%(data.sound,data.arg))
280 if data.sound == SoundRequest.ALL
and data.command == SoundRequest.PLAY_STOP:
284 sound.command(data.command)
285 except Exception
as e:
286 rospy.logerr(
'Exception in callback: %s'%str(e))
287 rospy.loginfo(traceback.format_exc())
290 rospy.logdebug(
"done callback")
295 for (key,sound)
in dict.iteritems():
297 staleness = sound.get_staleness()
298 except Exception
as e:
299 rospy.logerr(
'Exception in cleanupdict for sound (%s): %s'%(str(key),str(e)))
303 purgelist.append(key)
306 for key
in purgelist:
307 rospy.logdebug(
'Purging %s from cache'%key)
319 rospy.loginfo(
'Exception in cleanup: %s'%sys.exc_info()[0])
325 da = DiagnosticArray()
326 ds = DiagnosticStatus()
327 ds.name = rospy.get_caller_id().lstrip(
'/') +
": Node State"
329 ds.level = DiagnosticStatus.OK
331 ds.values.append(KeyValue(
"Active sounds", str(self.
active_sounds)))
332 ds.values.append(KeyValue(
"Allocated sound channels", str(self.
num_channels)))
333 ds.values.append(KeyValue(
"Buffered builtin sounds", str(len(self.
builtinsounds))))
334 ds.values.append(KeyValue(
"Buffered wave sounds", str(len(self.
filesounds))))
335 ds.values.append(KeyValue(
"Buffered voice sounds", str(len(self.
voicesounds))))
337 ds.level = DiagnosticStatus.WARN
338 ds.message =
"Sound device not open yet."
340 ds.level = DiagnosticStatus.ERROR
341 ds.message =
"Can't open sound device. See http://wiki.ros.org/sound_play/Troubleshooting"
343 da.header.stamp = rospy.get_rostime()
345 except Exception
as e:
346 rospy.loginfo(
'Exception in diagnostics: %s'%str(e))
349 data = data.sound_request
356 if data.sound == SoundRequest.ALL
and data.command == SoundRequest.PLAY_STOP:
360 sound.command(data.command)
363 start_time = rospy.get_rostime()
365 while sound.get_playing():
367 if self.
_as.is_preempt_requested():
368 rospy.loginfo(
'sound_play action: Preempted')
370 self.
_as.set_preempted()
374 self.
_feedback.playing = sound.get_playing()
375 self.
_feedback.stamp = rospy.get_rostime() - start_time
382 rospy.loginfo(
'sound_play action: Succeeded')
385 except Exception
as e:
386 rospy.logerr(
'Exception in actionlib callback: %s'%str(e))
387 rospy.loginfo(traceback.format_exc())
390 rospy.logdebug(
"done actionlib callback")
393 rospy.init_node(
'sound_play')
394 self.
device = rospy.get_param(
"~device", str())
395 self.
diagnostic_pub = rospy.Publisher(
"/diagnostics", DiagnosticArray, queue_size=1)
396 rootdir = os.path.join(roslib.packages.get_pkg_dir(
'sound_play'),
'sounds')
399 SoundRequest.BACKINGUP : (os.path.join(rootdir,
'BACKINGUP.ogg'), 0.1),
400 SoundRequest.NEEDS_UNPLUGGING : (os.path.join(rootdir,
'NEEDS_UNPLUGGING.ogg'), 1),
401 SoundRequest.NEEDS_PLUGGING : (os.path.join(rootdir,
'NEEDS_PLUGGING.ogg'), 1),
402 SoundRequest.NEEDS_UNPLUGGING_BADLY : (os.path.join(rootdir,
'NEEDS_UNPLUGGING_BADLY.ogg'), 1),
403 SoundRequest.NEEDS_PLUGGING_BADLY : (os.path.join(rootdir,
'NEEDS_PLUGGING_BADLY.ogg'), 1),
411 sub = rospy.Subscriber(
"robotsound", SoundRequest, self.
callback)
419 while not rospy.is_shutdown():
420 while not rospy.is_shutdown():
430 rospy.loginfo(
'Exception in idle_loop: %s'%sys.exc_info()[0])
444 rospy.loginfo(
'sound_play node is ready to play sound')
448 rospy.sleep(duration)
449 except rospy.exceptions.ROSInterruptException:
456 and not rospy.is_shutdown():
463 if __name__ ==
'__main__':