sound_play::SoundClient Class Reference

Class that publishes messages to the sound_play node. More...

#include <sound_play.h>

List of all members.

Classes

class  Sound

Public Member Functions

Sound builtinSound (int id)
 Create a builtin Sound.
void play (int sound)
 Play a buildin sound.
void playWave (const std::string &s)
 Plays a WAV or OGG file.
void repeat (const std::string &s)
 Say a string repeatedly.
void say (const std::string &s)
 Say a string.
void setQuiet (bool state)
 Turns warning messages on or off.
 SoundClient ()
 Create a SoundClient with the default topic.
 SoundClient (ros::NodeHandle &nh, const std::string &topic)
 Create a SoundClient that publishes on the given topic.
void start (int sound)
 Play a buildin sound repeatedly.
void startWave (const std::string &s)
 Plays a WAV or OGG file repeatedly.
void stop (int sound)
 Stop playing a built-in sound.
void stopAll ()
 Stop all currently playing sounds.
void stopSaying (const std::string &s)
 Stop saying a string.
void stopWave (const std::string &s)
 Stop playing a WAV or OGG file.
Sound voiceSound (const std::string &s)
 Create a voice Sound.
Sound waveSound (const std::string &s)
 Create a wave Sound.

Private Member Functions

void init (ros::NodeHandle nh, const std::string &topic)
void sendMsg (int snd, int cmd, const std::string &s="")

Private Attributes

boost::mutex mutex_
ros::NodeHandle nh_
ros::Publisher pub_
bool quiet_

Detailed Description

Class that publishes messages to the sound_play node.

This class is a helper class for communicating with the sound_play node via the sound_play::SoundRequest message. It has two ways of being used:

Definition at line 59 of file sound_play.h.


Constructor & Destructor Documentation

sound_play::SoundClient::SoundClient ( ros::NodeHandle &  nh,
const std::string &  topic 
) [inline]

Create a SoundClient that publishes on the given topic.

Creates a SoundClient that publishes to the given topic relative to the given NodeHandle.

Parameters:
nh Node handle to use when creating the topic.
topic Topic to publish to.

Definition at line 107 of file sound_play.h.

sound_play::SoundClient::SoundClient (  )  [inline]

Create a SoundClient with the default topic.

Creates a SoundClient that publishes to "robotsound".

Definition at line 117 of file sound_play.h.


Member Function Documentation

Sound sound_play::SoundClient::builtinSound ( int  id  )  [inline]

Create a builtin Sound.

Creates a Sound corresponding to indicated builtin wave.

Parameters:
id Identifier of the sound to play.

Definition at line 157 of file sound_play.h.

void sound_play::SoundClient::init ( ros::NodeHandle  nh,
const std::string &  topic 
) [inline, private]

Definition at line 303 of file sound_play.h.

void sound_play::SoundClient::play ( int  sound  )  [inline]

Play a buildin sound.

Starts playing one of the built-in sounds. built-ing sounds are documented in SoundRequest::msg. Playback can be stopped by stopAll.

Parameters:
sound Identifier of the sound to play.

Definition at line 248 of file sound_play.h.

void sound_play::SoundClient::playWave ( const std::string &  s  )  [inline]

Plays a WAV or OGG file.

Plays a WAV or OGG file once. The playback can be stopped by stopWave or stopAll.

Parameters:
s Filename of the WAV or OGG file. Must be an absolute path valid on the computer on which the sound_play node is running

Definition at line 209 of file sound_play.h.

void sound_play::SoundClient::repeat ( const std::string &  s  )  [inline]

Say a string repeatedly.

The string is said repeatedly until stopSaying or stopAll is used.

Parameters:
s String to say repeatedly

Definition at line 182 of file sound_play.h.

void sound_play::SoundClient::say ( const std::string &  s  )  [inline]

Say a string.

Send a string to be said by the sound_node. The vocalization can be stopped using stopSaying or stopAll.

Parameters:
s String to say

Definition at line 170 of file sound_play.h.

void sound_play::SoundClient::sendMsg ( int  snd,
int  cmd,
const std::string &  s = "" 
) [inline, private]

Definition at line 310 of file sound_play.h.

void sound_play::SoundClient::setQuiet ( bool  state  )  [inline]

Turns warning messages on or off.

If a message is sent when no node is subscribed to the topic, a warning message is printed. This method can be used to enable or disable warnings.

Parameters:
state True to turn off messages, false to turn them on.

Definition at line 297 of file sound_play.h.

void sound_play::SoundClient::start ( int  sound  )  [inline]

Play a buildin sound repeatedly.

Starts playing one of the built-in sounds repeatedly until stop or stopAll is used. Built-in sounds are documented in SoundRequest::msg.

Parameters:
sound Identifier of the sound to play.

Definition at line 261 of file sound_play.h.

void sound_play::SoundClient::startWave ( const std::string &  s  )  [inline]

Plays a WAV or OGG file repeatedly.

Plays a WAV or OGG file repeatedly until stopWave or stopAll is used.

Parameters:
s Filename of the WAV or OGG file. Must be an absolute path valid on the computer on which the sound_play node is running.

Definition at line 222 of file sound_play.h.

void sound_play::SoundClient::stop ( int  sound  )  [inline]

Stop playing a built-in sound.

Stops playing a built-in sound started with play or start.

Parameters:
sound Same sound that was used to start playback.

Definition at line 273 of file sound_play.h.

void sound_play::SoundClient::stopAll (  )  [inline]

Stop all currently playing sounds.

This method stops all speech, wave file, and built-in sound playback.

Definition at line 283 of file sound_play.h.

void sound_play::SoundClient::stopSaying ( const std::string &  s  )  [inline]

Stop saying a string.

Stops saying a string that was previously started by say or repeat. The argument indicates which string to stop saying.

Parameters:
s Same string as in the say or repeat command

Definition at line 195 of file sound_play.h.

void sound_play::SoundClient::stopWave ( const std::string &  s  )  [inline]

Stop playing a WAV or OGG file.

Stops playing a file that was previously started by playWave or startWave.

Parameters:
s Same string as in the playWave or startWave command

Definition at line 235 of file sound_play.h.

Sound sound_play::SoundClient::voiceSound ( const std::string &  s  )  [inline]

Create a voice Sound.

Creates a Sound corresponding to saying the indicated text.

Parameters:
s Text to say

Definition at line 130 of file sound_play.h.

Sound sound_play::SoundClient::waveSound ( const std::string &  s  )  [inline]

Create a wave Sound.

Creates a Sound corresponding to indicated file.

Parameters:
s File to play. Should be an absolute path that exists on the machine running the sound_play node.

Definition at line 144 of file sound_play.h.


Member Data Documentation

boost::mutex sound_play::SoundClient::mutex_ [private]

Definition at line 330 of file sound_play.h.

ros::NodeHandle sound_play::SoundClient::nh_ [private]

Definition at line 328 of file sound_play.h.

ros::Publisher sound_play::SoundClient::pub_ [private]

Definition at line 329 of file sound_play.h.

Definition at line 327 of file sound_play.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerator Friends


sound_play
Author(s): Blaise Gassend
autogenerated on Fri Jan 11 09:40:54 2013