3 import roslib; roslib.load_manifest(
'sound_play')
6 from sound_play.msg
import SoundRequest, SoundRequestAction, SoundRequestGoal
13 client.wait_for_server()
15 rospy.loginfo(
"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()
24 rospy.loginfo(
"End Need Unplugging")
26 rospy.loginfo(
"Need Plugging")
27 goal = SoundRequestGoal()
28 goal.sound_request.sound = SoundRequest.NEEDS_PLUGGING
29 goal.sound_request.command = SoundRequest.PLAY_ONCE
30 goal.sound_request.volume = volume
31 client.send_goal(goal)
32 client.wait_for_result()
34 rospy.loginfo(
"End Need Plugging")
37 goal = SoundRequestGoal()
38 goal.sound_request.sound = SoundRequest.SAY
39 goal.sound_request.command = SoundRequest.PLAY_ONCE
40 goal.sound_request.arg =
"Testing the actionlib interface A P I" 41 goal.sound_request.volume = volume
42 client.send_goal(goal)
43 client.wait_for_result()
45 rospy.loginfo(
"End Say")
48 goal = SoundRequestGoal()
49 goal.sound_request.sound = SoundRequest.PLAY_FILE
50 goal.sound_request.command = SoundRequest.PLAY_ONCE
51 goal.sound_request.arg = os.path.join(roslib.packages.get_pkg_dir(
'sound_play'),
'sounds') +
"/say-beep.wav" 52 goal.sound_request.volume = volume
53 client.send_goal(goal)
54 client.wait_for_result()
56 rospy.loginfo(
"End wav")
58 if __name__ ==
'__main__':
59 rospy.init_node(
'soundplay_client_test')
def sound_play_client(volume=1.0)