Gazebo Gazebo

API Reference

3.15.1
ignition::gazebo::logical_audio Namespace Reference

Classes

struct  Microphone
 Properties of a logical audio microphone. A microphone also has a pose, which can be stored as a component of a microphone entity via gz::sim::components::Pose. More...
 
struct  Source
 Properties of a logical audio source. A source also has a pose, which can be stored as a component of a source entity via gz::sim::components::Pose. More...
 
struct  SourcePlayInfo
 A source's playing information. Useful for keeping track of when to start/stop playing a source. More...
 

Enumerations

enum  AttenuationFunction { LINEAR, UNDEFINED }
 Audio source attenuation functions. AttenuationFunction::Undefined is used to indicate that an attenuation function has not been defined yet. More...
 
enum  AttenuationShape { SPHERE, UNDEFINED }
 Audio source attenuation shapes. AttenuationShape::Undefined is used to indicate that an attenuation shape has not been defined yet. More...
 

Functions

double computeVolume (bool _playing, AttenuationFunction _attenuationFunc, AttenuationShape _attenuationShape, double _sourceEmissionVolume, double _innerRadius, double _falloffDistance, const gz::math::Pose3d &_sourcePose, const gz::math::Pose3d &_targetPose)
 Computes the volume level of an audio source at a certain location. More...
 
bool detect (double _volumeLevel, double _volumeDetectionThreshold)
 Determines if an audio device can detect volume at a certain level. More...
 
void setAttenuationFunction (AttenuationFunction &_attenuationFunc, std::string _str)
 Set the attenuation function that matches the defined string. The string is not case sensitive, and must match the spelling of the values in AttenuationFunction. If the spelling does not match, the attenuation function is set as AttenuationFunction::Undefined. More...
 
void setAttenuationShape (AttenuationShape &_attenuationShape, std::string _str)
 Set the attenuation shape that matches the defined string. The string is not case sensitive, and must match the spelling of the values in AttenuationShape. If the spelling does not match, the attenuation shape is set as AttenuationShape::Undefined. More...
 
void validateInnerRadiusAndFalloffDistance (double &_innerRadius, double &_falloffDistance)
 Validate the inner radius and falloff distance for an audio source. More...
 
void validateVolumeLevel (double &_volumeLevel)
 Validate a source's emission volume level. More...
 

Enumeration Type Documentation

◆ AttenuationFunction

enum AttenuationFunction
strong

Audio source attenuation functions. AttenuationFunction::Undefined is used to indicate that an attenuation function has not been defined yet.

Enumerator
LINEAR 
UNDEFINED 

◆ AttenuationShape

enum AttenuationShape
strong

Audio source attenuation shapes. AttenuationShape::Undefined is used to indicate that an attenuation shape has not been defined yet.

Enumerator
SPHERE 
UNDEFINED 

Function Documentation

◆ computeVolume()

double ignition::gazebo::logical_audio::computeVolume ( bool  _playing,
AttenuationFunction  _attenuationFunc,
AttenuationShape  _attenuationShape,
double  _sourceEmissionVolume,
double  _innerRadius,
double  _falloffDistance,
const gz::math::Pose3d _sourcePose,
const gz::math::Pose3d _targetPose 
)

Computes the volume level of an audio source at a certain location.

Note
Users should call logical_audio::ValidateInnerRadiusAndFalloffDistance and logical_audio::ValidateVolumeLevel before calling this method in order to prevent undefined behavior.
Parameters
[in]_playingWhether the audio source is playing or not.
[in]_attenuationFuncThe source's attenuation function.
[in]_attenuationShapeThe source's attenuation shape.
[in]_sourceEmissionVolumeThe source's emission volume level.
[in]_innerRadiusThe source's inner radius, which should be >= 0.
[in]_falloffDistanceThe source's falloffDistance, which should be greater than _innerRadius.
[in]_sourcePoseThe source's pose.
[in]_targetPoseThe pose where the volume level should be calculated.
Returns
The volume level at this location. If the attenuation function or shape is undefined, -1.0 is returned. If the source is not playing, 0.0 is returned.

◆ detect()

bool ignition::gazebo::logical_audio::detect ( double  _volumeLevel,
double  _volumeDetectionThreshold 
)

Determines if an audio device can detect volume at a certain level.

Parameters
[in]_volumeLevelThe volume level that the microphone is attempting to detect. This should be a value between 0.0 (no volume) and 1.0 (maximum volume).
[in]_volumeDetectionThresholdThe listening device's minimum audio detection volume. This should be a value between 0.0 and 1.0. A device with a low detection threshold can hear a wider range of audio than a device with a higher detection threshold.
Returns
true if the listening device can detect volume at _volumeLevel, false otherwise.

◆ setAttenuationFunction()

void ignition::gazebo::logical_audio::setAttenuationFunction ( AttenuationFunction _attenuationFunc,
std::string  _str 
)

Set the attenuation function that matches the defined string. The string is not case sensitive, and must match the spelling of the values in AttenuationFunction. If the spelling does not match, the attenuation function is set as AttenuationFunction::Undefined.

Example: to set the attenuation function to AttenuationFunction::Linear, the following are examples of valid strings: "linear", "Linear", "LINEAR"

Parameters
[out]_attenuationFuncA reference to the variable that stores the calculated attenuation function.
[in]_strA string that should map to a value in AttenuationFunction.

◆ setAttenuationShape()

void ignition::gazebo::logical_audio::setAttenuationShape ( AttenuationShape _attenuationShape,
std::string  _str 
)

Set the attenuation shape that matches the defined string. The string is not case sensitive, and must match the spelling of the values in AttenuationShape. If the spelling does not match, the attenuation shape is set as AttenuationShape::Undefined.

Example: to set the attenuation shape to AttenuationShape::Sphere, the following are examples of valid strings: "sphere", "Sphere", "SPHERE"

Parameters
[out]_attenuationShapeA reference to the variable that stores the calculated attenuation shape.
[in]_strA string that should map to a value in AttenuationShape.

◆ validateInnerRadiusAndFalloffDistance()

void ignition::gazebo::logical_audio::validateInnerRadiusAndFalloffDistance ( double &  _innerRadius,
double &  _falloffDistance 
)

Validate the inner radius and falloff distance for an audio source.

Parameters
[in,out]_innerRadiusThe inner radius to set for the source. This value must be > 0. If the value of this parameter is < 0, the source's inner radius will be set to 0.
[in,out]_falloffDistanceThe falloff distance to set for the source. This value must be greater than _innerRadius. If _falloffDistance < _innerRadius, _falloffDistance will be set to _innerRadius + 1 (assuming that _innerRadius is valid).

◆ validateVolumeLevel()

void ignition::gazebo::logical_audio::validateVolumeLevel ( double &  _volumeLevel)

Validate a source's emission volume level.

Parameters
[in,out]_volumeLevelThe volume the source should play at. This parameter is checked (and possibly clipped) to ensure that it falls between 0.0 (0% volume) and 1.0 (100% volume).