Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
sound_play::SoundClient Class Reference

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

#include <sound_play.h>

Classes

class  Sound
 

Public Member Functions

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

Private Member Functions

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

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 61 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
nhNode handle to use when creating the topic.
topicTopic to publish to.

Definition at line 122 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 131 of file sound_play.h.

Member Function Documentation

Sound sound_play::SoundClient::builtinSound ( int  id,
float  volume = 1.0f 
)
inline

Create a builtin Sound.

Creates a Sound corresponding to indicated builtin wave.

Parameters
idIdentifier of the sound to play.
volumeVolume at which to play the sound. 0 is mute, 1.0 is 100%.

Definition at line 182 of file sound_play.h.

void sound_play::SoundClient::init ( ros::NodeHandle  nh,
const std::string &  topic 
)
inlineprivate

Definition at line 366 of file sound_play.h.

void sound_play::SoundClient::play ( int  sound,
float  volume = 1.0f 
)
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
soundIdentifier of the sound to play.
volumeVolume at which to play the sound. 0 is mute, 1.0 is 100%.

Definition at line 314 of file sound_play.h.

void sound_play::SoundClient::playWave ( const std::string &  s,
float  volume = 1.0f 
)
inline

Plays a WAV or OGG file.

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

Parameters
sFilename of the WAV or OGG file. Must be an absolute path valid on the computer on which the sound_play node is running
volumeVolume at which to play the sound. 0 is mute, 1.0 is 100%.

Definition at line 233 of file sound_play.h.

void sound_play::SoundClient::playWaveFromPkg ( const std::string &  p,
const std::string &  s,
float  volume = 1.0f 
)
inline

Plays a WAV or OGG file from a package.

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

Parameters
pPackage name containing the sound file.
sFilename of the WAV or OGG file. Must be an path relative to the package valid on the computer on which the sound_play node is running
volumeVolume at which to play the sound. 0 is mute, 1.0 is 100%.

Definition at line 273 of file sound_play.h.

void sound_play::SoundClient::repeat ( const std::string &  s,
float  volume = 1.0f 
)
inline

Say a string repeatedly.

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

Parameters
sString to say repeatedly
volumeVolume at which to play the sound. 0 is mute, 1.0 is 100%.

Definition at line 207 of file sound_play.h.

void sound_play::SoundClient::say ( const std::string &  s,
const std::string &  voice = "voice_kal_diphone",
float  volume = 1.0f 
)
inline

Say a string.

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

Parameters
sString to say
volumeVolume at which to play the sound. 0 is mute, 1.0 is 100%.

Definition at line 195 of file sound_play.h.

void sound_play::SoundClient::sendMsg ( int  snd,
int  cmd,
const std::string &  s = "",
const std::string &  arg2 = "",
const float &  vol = 1.0f 
)
inlineprivate

Definition at line 373 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
stateTrue to turn off messages, false to turn them on.

Definition at line 360 of file sound_play.h.

void sound_play::SoundClient::start ( int  sound,
float  volume = 1.0f 
)
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
soundIdentifier of the sound to play.
volumeVolume at which to play the sound. 0 is mute, 1.0 is 100%.

Definition at line 327 of file sound_play.h.

void sound_play::SoundClient::startWave ( const std::string &  s,
float  volume = 1.0f 
)
inline

Plays a WAV or OGG file repeatedly.

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

Parameters
sFilename of the WAV or OGG file. Must be an absolute path valid on the computer on which the sound_play node is running.
volumeVolume at which to play the sound. 0 is mute, 1.0 is 100%.

Definition at line 246 of file sound_play.h.

void sound_play::SoundClient::startWaveFromPkg ( const std::string &  p,
const std::string &  s,
float  volume = 1.0f 
)
inline

Plays a WAV or OGG file repeatedly.

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

Parameters
pPackage name containing the sound file.
sFilename of the WAV or OGG file. Must be an path relative to the package valid on the computer on which the sound_play node is running
volumeVolume at which to play the sound. 0 is mute, 1.0 is 100%.

Definition at line 287 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
soundSame sound that was used to start playback.

Definition at line 338 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 347 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
sSame string as in the say or repeat command

Definition at line 219 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
sSame string as in the playWave or startWave command

Definition at line 258 of file sound_play.h.

void sound_play::SoundClient::stopWaveFromPkg ( const std::string &  p,
const std::string &  s 
)
inline

Stop playing a WAV or OGG file.

Stops playing a file that was previously started by playWaveFromPkg or startWaveFromPkg.

Parameters
pPackage name containing the sound file.
sFilename of the WAV or OGG file. Must be an path relative to the package valid on the computer on which the sound_play node is running

Definition at line 301 of file sound_play.h.

Sound sound_play::SoundClient::voiceSound ( const std::string &  s,
float  volume = 1.0f 
)
inline

Create a voice Sound.

Creates a Sound corresponding to saying the indicated text.

Parameters
sText to say
volumeVolume at which to play the sound. 0 is mute, 1.0 is 100%.

Definition at line 143 of file sound_play.h.

Sound sound_play::SoundClient::waveSound ( const std::string &  s,
float  volume = 1.0f 
)
inline

Create a wave Sound.

Creates a Sound corresponding to indicated file.

Parameters
sFile to play. Should be an absolute path that exists on the machine running the sound_play node.
volumeVolume at which to play the sound. 0 is mute, 1.0 is 100%.

Definition at line 156 of file sound_play.h.

Sound sound_play::SoundClient::waveSoundFromPkg ( const std::string &  p,
const std::string &  s,
float  volume = 1.0f 
)
inline

Create a wave Sound from a package.

Creates a Sound corresponding to indicated file.

Parameters
pPackage containing the sound file.
sFilename of the WAV or OGG file. Must be an path relative to the package valid on the computer on which the sound_play node is running
volumeVolume at which to play the sound. 0 is mute, 1.0 is 100%.

Definition at line 170 of file sound_play.h.

Member Data Documentation

boost::mutex sound_play::SoundClient::mutex_
private

Definition at line 403 of file sound_play.h.

ros::NodeHandle sound_play::SoundClient::nh_
private

Definition at line 401 of file sound_play.h.

ros::Publisher sound_play::SoundClient::pub_
private

Definition at line 402 of file sound_play.h.

bool sound_play::SoundClient::quiet_
private

Definition at line 400 of file sound_play.h.


The documentation for this class was generated from the following file:


sound_play
Author(s): Blaise Gassend
autogenerated on Fri Apr 9 2021 02:41:17