OpenALSource Class Reference

OpenAL Source. More...

#include <OpenAL.hh>

Public Member Functions

 OpenALSource ()
 Constructor. More...
 
virtual ~OpenALSource ()
 Destructor. More...
 
std::vector< std::string > CollisionNames () const
 Get a vector of all the collision names. More...
 
void FillBufferFromFile (const std::string &_audioFile)
 Fill the OpenAL audio buffer with data from a sound file. More...
 
bool FillBufferFromPCM (uint8_t *_pcmData, unsigned int _dataCount, int _sampleRate)
 Fill the OpenAL audio buffer from PCM data. More...
 
std::vector< std::string > GetCollisionNames () const GAZEBO_DEPRECATED(7.0)
 Get a vector of all the collision names. More...
 
bool GetOnContact () const GAZEBO_DEPRECATED(7.0)
 Return true if the audio source is played on contact with another object. More...
 
bool HasCollisionName (const std::string &_name) const
 Get whether the source has a collision name set. More...
 
bool IsPlaying ()
 Is the audio playing. More...
 
bool Load (sdf::ElementPtr _sdf)
 Load the source from sdf. More...
 
bool OnContact () const
 Return true if the audio source is played on contact with another object. More...
 
void Pause ()
 Pause a sound. More...
 
void Play ()
 Play a sound. More...
 
void Rewind ()
 Rewind the sound to the beginning. More...
 
bool SetGain (float _g)
 Set the pitch of the source. More...
 
bool SetLoop (bool _state)
 Set whether the source loops the audio. More...
 
bool SetPitch (float _p)
 Set the pitch of the source. More...
 
bool SetPose (const ignition::math::Pose3d &_pose)
 Set the position of the source. More...
 
bool SetVelocity (const ignition::math::Vector3d &_vel)
 Set the velocity of the source. More...
 
void Stop ()
 Stop a sound. More...
 

Detailed Description

OpenAL Source.

This can be thought of as a speaker.

Constructor & Destructor Documentation

Constructor.

virtual ~OpenALSource ( )
virtual

Destructor.

Member Function Documentation

std::vector<std::string> CollisionNames ( ) const

Get a vector of all the collision names.

Returns
All the collision names used to trigger audio playback on contact.
void FillBufferFromFile ( const std::string &  _audioFile)

Fill the OpenAL audio buffer with data from a sound file.

Parameters
[in]_audioFileName and an audio file.
bool FillBufferFromPCM ( uint8_t *  _pcmData,
unsigned int  _dataCount,
int  _sampleRate 
)

Fill the OpenAL audio buffer from PCM data.

Parameters
[in]_pcmDataPointer to the PCM audio data.
[in]_dataCountSize of the PCM data.
[in]_sampleRateSample rate for the PCM data.
Returns
True on success.
std::vector<std::string> GetCollisionNames ( ) const

Get a vector of all the collision names.

Returns
All the collision names used to trigger audio playback on contact.
Deprecated:
See CollisionNames() const
bool GetOnContact ( ) const

Return true if the audio source is played on contact with another object.

Contact is determine based on a set of collision objects.

Returns
True if audio is played on contact.
See Also
AddCollision()
Deprecated:
See OnContact() const
bool HasCollisionName ( const std::string &  _name) const

Get whether the source has a collision name set.

Parameters
[in]_nameName of a collision to check for.
Returns
True if the collision name was found.
bool IsPlaying ( )

Is the audio playing.

bool Load ( sdf::ElementPtr  _sdf)

Load the source from sdf.

Parameters
[in]_sdfSDF element parameters for an audio_source.
Returns
True on success.
bool OnContact ( ) const

Return true if the audio source is played on contact with another object.

Contact is determine based on a set of collision objects.

Returns
True if audio is played on contact.
See Also
AddCollision()
void Pause ( )

Pause a sound.

void Play ( )

Play a sound.

void Rewind ( )

Rewind the sound to the beginning.

bool SetGain ( float  _g)

Set the pitch of the source.

Parameters
[in]_gGain value.
Returns
True on success.
bool SetLoop ( bool  _state)

Set whether the source loops the audio.

Parameters
[in]_stateTrue to cause playback to loop.
Returns
True on success.
bool SetPitch ( float  _p)

Set the pitch of the source.

Parameters
[in]_pPitch value.
Returns
True on success.
bool SetPose ( const ignition::math::Pose3d &  _pose)

Set the position of the source.

Parameters
[in]_poseNew pose of the source.
Returns
True on success.
bool SetVelocity ( const ignition::math::Vector3d &  _vel)

Set the velocity of the source.

Parameters
[in]_velNew velocity of the source.
Returns
True on success.
void Stop ( )

Stop a sound.


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