Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include <sound_play/sound_play.h>
00037 #include <unistd.h>
00038
00039 void sleepok(int t, ros::NodeHandle &nh)
00040 {
00041 if (nh.ok())
00042 sleep(t);
00043 }
00044
00045 int main(int argc, char **argv)
00046 {
00047 ros::init(argc, argv, "sound_play_test");
00048
00049 ros::NodeHandle nh;
00050 sound_play::SoundClient sc;
00051
00052 sleepok(1, nh);
00053
00054 while(nh.ok())
00055 {
00056 sc.say("Hello world!");
00057 sleepok(2, nh);
00058
00059 const char *str1 = "I am annoying.";
00060 sc.repeat(str1);
00061 sleepok(4, nh);
00062 sc.stopSaying(str1);
00063
00064 sc.playWave("/usr/share/xemacs21/xemacs-packages/etc/sounds/boing.wav");
00065 sleepok(2, nh);
00066
00067 const char *str2 = "/usr/share/xemacs21/xemacs-packages/etc/sounds/piano-beep.wav";
00068 sc.startWave(str2);
00069 sleepok(4, nh);
00070 sc.stopWave(str2);
00071
00072 sc.play(sound_play::SoundRequest::NEEDS_UNPLUGGING);
00073 sleepok(2, nh);
00074
00075 sc.start(sound_play::SoundRequest::BACKINGUP);
00076 sleepok(4, nh);
00077 sc.stop(sound_play::SoundRequest::BACKINGUP);
00078
00079 sleepok(2, nh);
00080 sound_play::Sound s1 = sc.waveSound("/usr/share/xemacs21/xemacs-packages/etc/sounds/boing.wav");
00081 s1.repeat();
00082 sleepok(1, nh);
00083 s1.stop();
00084
00085 sleepok(2, nh);
00086 sound_play::Sound s2 = sc.voiceSound("This is a really long sentence that will get cut off.");
00087 s2.play();
00088 sleepok(1, nh);
00089 s2.stop();
00090
00091 sleepok(2, nh);
00092 sound_play::Sound s3 = sc.builtinSound(sound_play::SoundRequest::NEEDS_UNPLUGGING_BADLY);
00093 s3.play();
00094 sleepok(1, nh);
00095 s3.stop();
00096 }
00097 }