3 import roslib; roslib.load_manifest(
'sound_play')
6 from sound_play.msg
import SoundRequest, SoundRequestAction, SoundRequestGoal
13 client.wait_for_server()
15 print "Need Unplugging" 16 goal = SoundRequestGoal()
17 goal.sound_request.sound = SoundRequest.NEEDS_UNPLUGGING
18 goal.sound_request.command = SoundRequest.PLAY_ONCE
19 goal.sound_request.volume = volume
21 client.send_goal(goal)
22 client.wait_for_result()
23 print client.get_result()
24 print "End Need Unplugging" 28 goal = SoundRequestGoal()
29 goal.sound_request.sound = SoundRequest.NEEDS_PLUGGING
30 goal.sound_request.command = SoundRequest.PLAY_ONCE
31 goal.sound_request.volume = volume
32 client.send_goal(goal)
33 client.wait_for_result()
34 print client.get_result()
35 print "End Need Plugging" 39 goal = SoundRequestGoal()
40 goal.sound_request.sound = SoundRequest.SAY
41 goal.sound_request.command = SoundRequest.PLAY_ONCE
42 goal.sound_request.arg =
"Testing the actionlib interface A P I" 43 goal.sound_request.volume = volume
44 client.send_goal(goal)
45 client.wait_for_result()
46 print client.get_result()
51 goal = SoundRequestGoal()
52 goal.sound_request.sound = SoundRequest.PLAY_FILE
53 goal.sound_request.command = SoundRequest.PLAY_ONCE
54 goal.sound_request.arg = os.path.join(roslib.packages.get_pkg_dir(
'sound_play'),
'sounds') +
"/say-beep.wav" 55 goal.sound_request.volume = volume
56 client.send_goal(goal)
57 client.wait_for_result()
58 print client.get_result()
62 if __name__ ==
'__main__':
63 rospy.init_node(
'soundplay_client_test')
def sound_play_client(volume=1.0)