soundplay_node.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 #***********************************************************
4 #* Software License Agreement (BSD License)
5 #*
6 #* Copyright (c) 2009, Willow Garage, Inc.
7 #* All rights reserved.
8 #*
9 #* Redistribution and use in source and binary forms, with or without
10 #* modification, are permitted provided that the following conditions
11 #* are met:
12 #*
13 #* * Redistributions of source code must retain the above copyright
14 #* notice, this list of conditions and the following disclaimer.
15 #* * Redistributions in binary form must reproduce the above
16 #* copyright notice, this list of conditions and the following
17 #* disclaimer in the documentation and/or other materials provided
18 #* with the distribution.
19 #* * Neither the name of the Willow Garage nor the names of its
20 #* contributors may be used to endorse or promote products derived
21 #* from this software without specific prior written permission.
22 #*
23 #* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24 #* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25 #* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26 #* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27 #* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28 #* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29 #* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30 #* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31 #* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32 #* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33 #* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34 #* POSSIBILITY OF SUCH DAMAGE.
35 #***********************************************************
36 
37 # Author: Blaise Gassend
38 
39 import roslib
40 import rospy
41 import threading
42 import os
43 import logging
44 import sys
45 import traceback
46 import tempfile
47 from diagnostic_msgs.msg import DiagnosticStatus, KeyValue, DiagnosticArray
48 from sound_play.msg import SoundRequest, SoundRequestAction, SoundRequestResult, SoundRequestFeedback
49 import actionlib
50 
51 try:
52  import gi
53  gi.require_version('Gst', '1.0')
54  from gi.repository import Gst as Gst
55 except:
56  str="""
57 **************************************************************
58 Error opening pygst. Is gstreamer installed?
59 **************************************************************
60 """
61  rospy.logfatal(str)
62  print str
63  exit(1)
64 
65 def sleep(t):
66  try:
67  rospy.sleep(t)
68  except:
69  pass
70 
71 
72 class soundtype:
73  STOPPED = 0
74  LOOPING = 1
75  COUNTING = 2
76 
77  def __init__(self, file, device, volume = 1.0):
78  self.lock = threading.RLock()
79  self.state = self.STOPPED
80  self.sound = Gst.ElementFactory.make("playbin",None)
81  if self.sound is None:
82  raise Exception("Could not create sound player")
83 
84  if device:
85  self.sink = Gst.ElementFactory.make("alsasink", "sink")
86  self.sink.set_property("device", device)
87  self.sound.set_property("audio-sink", self.sink)
88 
89  if (":" in file):
90  uri = file
91  elif os.path.isfile(file):
92  uri = "file://" + os.path.abspath(file)
93  else:
94  rospy.logerr('Error: URI is invalid: %s'%file)
95 
96  self.uri = uri
97  self.volume = volume
98  self.sound.set_property('uri', uri)
99  self.sound.set_property("volume",volume)
100  self.staleness = 1
101  self.file = file
102 
103  self.bus = self.sound.get_bus()
104  self.bus.add_signal_watch()
105  self.bus.connect("message", self.on_stream_end)
106 
107  def on_stream_end(self, bus, message):
108  if message.type == Gst.MessageType.EOS:
109  self.state = self.STOPPED
110 
111  def __del__(self):
112  # stop our GST object so that it gets garbage-collected
113  self.stop()
114 
115  def update(self):
116  self.bus.poll(Gst.MessageType.ERROR, 10)
117 
118  def loop(self):
119  self.lock.acquire()
120  try:
121  self.staleness = 0
122  if self.state == self.COUNTING:
123  self.stop()
124 
125  if self.state == self.STOPPED:
126  self.sound.seek_simple(Gst.Format.TIME, Gst.SeekFlags.FLUSH, 0)
127  self.sound.set_state(Gst.State.PLAYING)
128  self.state = self.LOOPING
129  finally:
130  self.lock.release()
131 
132  def stop(self):
133  if self.state != self.STOPPED:
134  self.lock.acquire()
135  try:
136  self.sound.set_state(Gst.State.NULL)
137  self.state = self.STOPPED
138  finally:
139  self.lock.release()
140 
141  def single(self):
142  self.lock.acquire()
143  try:
144  rospy.logdebug("Playing %s"%self.uri)
145  self.staleness = 0
146  if self.state == self.LOOPING:
147  self.stop()
148 
149  self.sound.seek_simple(Gst.Format.TIME, Gst.SeekFlags.FLUSH, 0)
150  self.sound.set_state(Gst.State.PLAYING)
151  self.state = self.COUNTING
152  finally:
153  self.lock.release()
154 
155  def command(self, cmd):
156  if cmd == SoundRequest.PLAY_STOP:
157  self.stop()
158  elif cmd == SoundRequest.PLAY_ONCE:
159  self.single()
160  elif cmd == SoundRequest.PLAY_START:
161  self.loop()
162 
163  def get_staleness(self):
164  self.lock.acquire()
165  position = 0
166  duration = 0
167  try:
168  position = self.sound.query_position(Gst.Format.TIME)[0]
169  duration = self.sound.query_duration(Gst.Format.TIME)[0]
170  except Exception, e:
171  position = 0
172  duration = 0
173  finally:
174  self.lock.release()
175 
176  if position != duration:
177  self.staleness = 0
178  else:
179  self.staleness = self.staleness + 1
180  return self.staleness
181 
182  def get_playing(self):
183  return self.state == self.COUNTING
184 
185 class soundplay:
186  _feedback = SoundRequestFeedback()
187  _result = SoundRequestResult()
188 
189  def stopdict(self,dict):
190  for sound in dict.values():
191  sound.stop()
192 
193  def stopall(self):
194  self.stopdict(self.builtinsounds)
195  self.stopdict(self.filesounds)
196  self.stopdict(self.voicesounds)
197 
198  def select_sound(self, data):
199  if data.sound == SoundRequest.PLAY_FILE:
200  if not data.arg2:
201  if not data.arg in self.filesounds.keys():
202  rospy.logdebug('command for uncached wave: "%s"'%data.arg)
203  try:
204  self.filesounds[data.arg] = soundtype(data.arg, self.device, data.volume)
205  except:
206  rospy.logerr('Error setting up to play "%s". Does this file exist on the machine on which sound_play is running?'%data.arg)
207  return
208  else:
209  rospy.logdebug('command for cached wave: "%s"'%data.arg)
210  if self.filesounds[data.arg].sound.get_property('volume') != data.volume:
211  rospy.logdebug('volume for cached wave has changed, resetting volume')
212  self.filesounds[data.arg].sound.set_property('volume', data.volume)
213  sound = self.filesounds[data.arg]
214  else:
215  absfilename = os.path.join(roslib.packages.get_pkg_dir(data.arg2), data.arg)
216  if not absfilename in self.filesounds.keys():
217  rospy.logdebug('command for uncached wave: "%s"'%absfilename)
218  try:
219  self.filesounds[absfilename] = soundtype(absfilename, self.device, data.volume)
220  except:
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))
222  return
223  else:
224  rospy.logdebug('command for cached wave: "%s"'%absfilename)
225  if self.filesounds[absfilename].sound.get_property('volume') != data.volume:
226  rospy.logdebug('volume for cached wave has changed, resetting volume')
227  self.filesounds[absfilename].sound.set_property('volume', data.volume)
228  sound = self.filesounds[absfilename]
229  elif data.sound == SoundRequest.SAY:
230  print data
231  if not data.arg in self.voicesounds.keys():
232  rospy.logdebug('command for uncached text: "%s"' % data.arg)
233  txtfile = tempfile.NamedTemporaryFile(prefix='sound_play', suffix='.txt')
234  (wavfile,wavfilename) = tempfile.mkstemp(prefix='sound_play', suffix='.wav')
235  txtfilename=txtfile.name
236  os.close(wavfile)
237  voice = data.arg2
238  try:
239  txtfile.write(data.arg.decode('UTF-8').encode('ISO-8859-15'))
240  txtfile.flush()
241  os.system("text2wave -eval '("+voice+")' "+txtfilename+" -o "+wavfilename)
242  try:
243  if os.stat(wavfilename).st_size == 0:
244  raise OSError # So we hit the same catch block
245  except OSError:
246  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')
247  return
248  self.voicesounds[data.arg] = soundtype(wavfilename, self.device, data.volume)
249  finally:
250  txtfile.close()
251  else:
252  rospy.logdebug('command for cached text: "%s"'%data.arg)
253  if self.voicesounds[data.arg].sound.get_property('volume') != data.volume:
254  rospy.logdebug('volume for cached text has changed, resetting volume')
255  self.voicesounds[data.arg].sound.set_property('volume', data.volume)
256  sound = self.voicesounds[data.arg]
257  else:
258  rospy.logdebug('command for builtin wave: %i'%data.sound)
259  if data.sound not in self.builtinsounds or (data.sound in self.builtinsounds and data.volume != self.builtinsounds[data.sound].volume):
260  params = self.builtinsoundparams[data.sound]
261  volume = data.volume
262  if params[1] != 1: # use the second param as a scaling for the input volume
263  volume = (volume + params[1])/2
264  self.builtinsounds[data.sound] = soundtype(params[0], self.device, volume)
265  sound = self.builtinsounds[data.sound]
266  if sound.staleness != 0 and data.command != SoundRequest.PLAY_STOP:
267  # This sound isn't counted in active_sounds
268  rospy.logdebug("activating %i %s"%(data.sound,data.arg))
269  self.active_sounds = self.active_sounds + 1
270  sound.staleness = 0
271  # if self.active_sounds > self.num_channels:
272  # mixer.set_num_channels(self.active_sounds)
273  # self.num_channels = self.active_sounds
274  return sound
275 
276  def callback(self,data):
277  if not self.initialized:
278  return
279  self.mutex.acquire()
280  # Force only one sound at a time
281  self.stopall()
282  try:
283  if data.sound == SoundRequest.ALL and data.command == SoundRequest.PLAY_STOP:
284  self.stopall()
285  else:
286  sound = self.select_sound(data)
287  sound.command(data.command)
288  except Exception, e:
289  rospy.logerr('Exception in callback: %s'%str(e))
290  rospy.loginfo(traceback.format_exc())
291  finally:
292  self.mutex.release()
293  rospy.logdebug("done callback")
294 
295  # Purge sounds that haven't been played in a while.
296  def cleanupdict(self, dict):
297  purgelist = []
298  for (key,sound) in dict.iteritems():
299  try:
300  staleness = sound.get_staleness()
301  except Exception, e:
302  rospy.logerr('Exception in cleanupdict for sound (%s): %s'%(str(key),str(e)))
303  staleness = 100 # Something is wrong. Let's purge and try again.
304  #print "%s %i"%(key, staleness)
305  if staleness >= 10:
306  purgelist.append(key)
307  if staleness == 0: # Sound is playing
308  self.active_sounds = self.active_sounds + 1
309  for key in purgelist:
310  rospy.logdebug('Purging %s from cache'%key)
311  dict[key].stop() # clean up resources
312  del dict[key]
313 
314  def cleanup(self):
315  self.mutex.acquire()
316  try:
317  self.active_sounds = 0
318  self.cleanupdict(self.filesounds)
319  self.cleanupdict(self.voicesounds)
320  self.cleanupdict(self.builtinsounds)
321  except:
322  rospy.loginfo('Exception in cleanup: %s'%sys.exc_info()[0])
323  finally:
324  self.mutex.release()
325 
326  def diagnostics(self, state):
327  try:
328  da = DiagnosticArray()
329  ds = DiagnosticStatus()
330  ds.name = rospy.get_caller_id().lstrip('/') + ": Node State"
331  if state == 0:
332  ds.level = DiagnosticStatus.OK
333  ds.message = "%i sounds playing"%self.active_sounds
334  ds.values.append(KeyValue("Active sounds", str(self.active_sounds)))
335  ds.values.append(KeyValue("Allocated sound channels", str(self.num_channels)))
336  ds.values.append(KeyValue("Buffered builtin sounds", str(len(self.builtinsounds))))
337  ds.values.append(KeyValue("Buffered wave sounds", str(len(self.filesounds))))
338  ds.values.append(KeyValue("Buffered voice sounds", str(len(self.voicesounds))))
339  elif state == 1:
340  ds.level = DiagnosticStatus.WARN
341  ds.message = "Sound device not open yet."
342  else:
343  ds.level = DiagnosticStatus.ERROR
344  ds.message = "Can't open sound device. See http://wiki.ros.org/sound_play/Troubleshooting"
345  da.status.append(ds)
346  da.header.stamp = rospy.get_rostime()
347  self.diagnostic_pub.publish(da)
348  except Exception, e:
349  rospy.loginfo('Exception in diagnostics: %s'%str(e))
350 
351  def execute_cb(self, data):
352  data = data.sound_request
353  if not self.initialized:
354  return
355  self.mutex.acquire()
356  # Force only one sound at a time
357  self.stopall()
358  try:
359  if data.sound == SoundRequest.ALL and data.command == SoundRequest.PLAY_STOP:
360  self.stopall()
361  else:
362  sound = self.select_sound(data)
363  sound.command(data.command)
364 
365  r = rospy.Rate(1)
366  start_time = rospy.get_rostime()
367  success = True
368  while sound.get_playing():
369  sound.update()
370  if self._as.is_preempt_requested():
371  rospy.loginfo('sound_play action: Preempted')
372  sound.stop()
373  self._as.set_preempted()
374  success = False
375  break
376 
377  self._feedback.playing = sound.get_playing()
378  self._feedback.stamp = rospy.get_rostime() - start_time
379  self._as.publish_feedback(self._feedback)
380  r.sleep()
381 
382  if success:
383  self._result.playing = self._feedback.playing
384  self._result.stamp = self._feedback.stamp
385  rospy.loginfo('sound_play action: Succeeded')
386  self._as.set_succeeded(self._result)
387 
388  except Exception, e:
389  rospy.logerr('Exception in actionlib callback: %s'%str(e))
390  rospy.loginfo(traceback.format_exc())
391  finally:
392  self.mutex.release()
393  rospy.logdebug("done actionlib callback")
394 
395  def __init__(self):
396  Gst.init(None)
397  rospy.init_node('sound_play')
398  self.device = rospy.get_param("~device", "default")
399  self.diagnostic_pub = rospy.Publisher("/diagnostics", DiagnosticArray, queue_size=1)
400  rootdir = os.path.join(roslib.packages.get_pkg_dir('sound_play'),'sounds')
401 
403  SoundRequest.BACKINGUP : (os.path.join(rootdir, 'BACKINGUP.ogg'), 0.1),
404  SoundRequest.NEEDS_UNPLUGGING : (os.path.join(rootdir, 'NEEDS_UNPLUGGING.ogg'), 1),
405  SoundRequest.NEEDS_PLUGGING : (os.path.join(rootdir, 'NEEDS_PLUGGING.ogg'), 1),
406  SoundRequest.NEEDS_UNPLUGGING_BADLY : (os.path.join(rootdir, 'NEEDS_UNPLUGGING_BADLY.ogg'), 1),
407  SoundRequest.NEEDS_PLUGGING_BADLY : (os.path.join(rootdir, 'NEEDS_PLUGGING_BADLY.ogg'), 1),
408  }
409 
410  self.no_error = True
411  self.initialized = False
412  self.active_sounds = 0
413 
414  self.mutex = threading.Lock()
415  sub = rospy.Subscriber("robotsound", SoundRequest, self.callback)
416  self._as = actionlib.SimpleActionServer('sound_play', SoundRequestAction, execute_cb=self.execute_cb, auto_start = False)
417  self._as.start()
418 
419  self.mutex.acquire()
420  self.sleep(0.5) # For ros startup race condition
421  self.diagnostics(1)
422 
423  while not rospy.is_shutdown():
424  while not rospy.is_shutdown():
425  self.init_vars()
426  self.no_error = True
427  self.initialized = True
428  self.mutex.release()
429  try:
430  self.idle_loop()
431  # Returns after inactive period to test device availability
432  #print "Exiting idle"
433  except:
434  rospy.loginfo('Exception in idle_loop: %s'%sys.exc_info()[0])
435  finally:
436  self.mutex.acquire()
437 
438  self.diagnostics(2)
439  self.mutex.release()
440 
441  def init_vars(self):
442  self.num_channels = 10
443  self.builtinsounds = {}
444  self.filesounds = {}
445  self.voicesounds = {}
446  self.hotlist = []
447  if not self.initialized:
448  rospy.loginfo('sound_play node is ready to play sound')
449 
450  def sleep(self, duration):
451  try:
452  rospy.sleep(duration)
453  except rospy.exceptions.ROSInterruptException:
454  pass
455 
456  def idle_loop(self):
457  self.last_activity_time = rospy.get_time()
458  while (rospy.get_time() - self.last_activity_time < 10 or
459  len(self.builtinsounds) + len(self.voicesounds) + len(self.filesounds) > 0) \
460  and not rospy.is_shutdown():
461  #print "idle_loop"
462  self.diagnostics(0)
463  self.sleep(1)
464  self.cleanup()
465  #print "idle_exiting"
466 
467 if __name__ == '__main__':
468  soundplay()
def __init__(self, file, device, volume=1.0)
def sleep(self, duration)
def on_stream_end(self, bus, message)
def cleanupdict(self, dict)
def stop(self)
Stop Sound playback.
Definition: libsoundplay.py:86
def diagnostics(self, state)
def execute_cb(self, data)
def select_sound(self, data)
def callback(self, data)
def stopdict(self, dict)


sound_play
Author(s): Blaise Gassend
autogenerated on Tue Mar 26 2019 02:30:56