soundclient_example.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 """
4 Simple example showing how to use the SoundClient provided by libsoundplay,
5 in blocking, non-blocking, and explicit usage.
6 """
7 
8 import rospy
9 from sound_play.libsoundplay import SoundClient
10 from sound_play.msg import SoundRequest
11 
12 
14  rospy.loginfo('Example: SoundClient play methods can take in an explicit'
15  ' blocking parameter')
16  soundhandle = SoundClient() # blocking = False by default
17  rospy.sleep(0.5) # Ensure publisher connection is successful.
18 
19  sound_beep = soundhandle.waveSound("say-beep.wav", volume=0.5)
20  # Play the same sound twice, once blocking and once not. The first call is
21  # blocking (explicitly specified).
22  sound_beep.play(blocking=True)
23  # This call is not blocking (uses the SoundClient's setting).
24  sound_beep.play()
25  rospy.sleep(0.5) # Let sound complete.
26 
27  # Play a blocking sound.
28  soundhandle.play(SoundRequest.NEEDS_UNPLUGGING, blocking=True)
29 
30  # Create a new SoundClient where the default behavior *is* to block.
31  soundhandle = SoundClient(blocking=True)
32  soundhandle.say('Say-ing stuff while block-ing')
33  soundhandle.say('Say-ing stuff without block-ing', blocking=False)
34  rospy.sleep(1)
35 
36 
38  """
39  Play various sounds, blocking until each is completed before going to the
40  next.
41  """
42  rospy.loginfo('Example: Playing sounds in *blocking* mode.')
43  soundhandle = SoundClient(blocking=True)
44 
45  rospy.loginfo('Playing say-beep at full volume.')
46  soundhandle.playWave('say-beep.wav')
47 
48  rospy.loginfo('Playing say-beep at volume 0.3.')
49  soundhandle.playWave('say-beep.wav', volume=0.3)
50 
51  rospy.loginfo('Playing sound for NEEDS_PLUGGING.')
52  soundhandle.play(SoundRequest.NEEDS_PLUGGING)
53 
54  rospy.loginfo('Speaking some long string.')
55  soundhandle.say('It was the best of times, it was the worst of times.')
56 
57 
59  """
60  Play the same sounds with manual pauses between them.
61  """
62  rospy.loginfo('Example: Playing sounds in *non-blocking* mode.')
63  # NOTE: you must sleep at the beginning to let the SoundClient publisher
64  # establish a connection to the soundplay_node.
65  soundhandle = SoundClient(blocking=False)
66  rospy.sleep(1)
67 
68  # In the non-blocking version you need to sleep between calls.
69  rospy.loginfo('Playing say-beep at full volume.')
70  soundhandle.playWave('say-beep.wav')
71  rospy.sleep(1)
72 
73  rospy.loginfo('Playing say-beep at volume 0.3.')
74  soundhandle.playWave('say-beep.wav', volume=0.3)
75  rospy.sleep(1)
76 
77  rospy.loginfo('Playing sound for NEEDS_PLUGGING.')
78  soundhandle.play(SoundRequest.NEEDS_PLUGGING)
79  rospy.sleep(1)
80 
81  rospy.loginfo('Speaking some long string.')
82  soundhandle.say('It was the best of times, it was the worst of times.')
83  # Note we will return before the string has finished playing.
84 
85 
86 if __name__ == '__main__':
87  rospy.init_node('soundclient_example', anonymous=False)
91  rospy.loginfo('Finished')
This class is a helper class for communicating with the sound_play node via the sound_play.SoundRequest message.
Definition: libsoundplay.py:93


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