44 int main(
int argc,
char **argv)
56 sc.
say(
"Hello world!");
58 quiet_sc.
say(
"Hello world!");
61 const char *str1 =
"I am annoying.";
69 sc.
playWave(
"/usr/share/xemacs21/xemacs-packages/etc/sounds/boing.wav");
71 quiet_sc.
playWave(
"/usr/share/xemacs21/xemacs-packages/etc/sounds/boing.wav");
74 const char *str2 =
"/usr/share/xemacs21/xemacs-packages/etc/sounds/piano-beep.wav";
82 sc.
play(sound_play::SoundRequest::NEEDS_UNPLUGGING);
84 quiet_sc.
play(sound_play::SoundRequest::NEEDS_UNPLUGGING);
87 sc.
play(sound_play::SoundRequest::NEEDS_UNPLUGGING);
89 quiet_sc.
play(sound_play::SoundRequest::NEEDS_UNPLUGGING);
92 sc.
start(sound_play::SoundRequest::BACKINGUP);
94 sc.
stop(sound_play::SoundRequest::BACKINGUP);
95 quiet_sc.
start(sound_play::SoundRequest::BACKINGUP);
97 quiet_sc.
stop(sound_play::SoundRequest::BACKINGUP);
void play(int sound, float volume=1.0f)
Play a buildin sound.
void repeat()
Play the Sound repeatedly.
void repeat(const std::string &s, float volume=1.0f)
Say a string repeatedly.
void sleepok(int t, ros::NodeHandle &nh)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void stopSaying(const std::string &s)
Stop saying a string.
Sound builtinSound(int id, float volume=1.0f)
Create a builtin Sound.
void startWave(const std::string &s, float volume=1.0f)
Plays a WAV or OGG file repeatedly.
void play()
Play the Sound.
Sound waveSoundFromPkg(const std::string &p, const std::string &s, float volume=1.0f)
Create a wave Sound from a package.
void start(int sound, float volume=1.0f)
Play a buildin sound repeatedly.
Sound waveSound(const std::string &s, float volume=1.0f)
Create a wave Sound.
int main(int argc, char **argv)
Sound voiceSound(const std::string &s, float volume=1.0f)
Create a voice Sound.
void stopWave(const std::string &s)
Stop playing a WAV or OGG file.
void say(const std::string &s, const std::string &voice="voice_kal_diphone", float volume=1.0f)
Say a string.
void playWave(const std::string &s, float volume=1.0f)
Plays a WAV or OGG file.
Class that publishes messages to the sound_play node.
void stop()
Stop Sound playback.
void stop(int sound)
Stop playing a built-in sound.