Ignition Gazebo

API Reference

3.7.0
LogicalAudioSensorPlugin Class Reference

A plugin for logical audio detection. More...

#include <LogicalAudioSensorPlugin.hh>

Public Member Functions

 LogicalAudioSensorPlugin ()
 Constructor. More...
 
 ~LogicalAudioSensorPlugin () override
 Destructor. More...
 
void Configure (const Entity &_entity, const std::shared_ptr< const sdf::Element > &_sdf, EntityComponentManager &_ecm, EventManager &_eventMgr) override
 Documentation inherited. More...
 
void PostUpdate (const UpdateInfo &_info, const EntityComponentManager &_ecm) override
 Documentation inherited. More...
 
void PreUpdate (const UpdateInfo &_info, EntityComponentManager &_ecm) override
 
- Public Member Functions inherited from System
 System ()
 Constructor. More...
 
virtual ~System ()
 Destructor. More...
 

Detailed Description

A plugin for logical audio detection.

Each <plugin> tag can accept multiple sensors (sound sources and/or microphones). After each simulation step, microphones check if audio was detected by any sources in the world. No audio is actually played to an audio device such as speakers. This plugin is meant to check if audio could theoretically be heard at a certain location or not.

Secifying an audio source via SDF is done as follows:

<source> A new audio source in the environment, which has the following child elements:

  • <id> The source ID, which must be unique and an integer >= 0. An ID < 0 results in undefined behavior. The ID must be unique within the scope of all other source IDs in the plugin's parent element - so, if a source was created in a <model> with an ID of 1, no other sources in the same model can have an ID of 1 (however, sources that belong to other models can have an ID of 1).
  • <pose> The pose, expressed as "x y z roll pitch yaw". Each pose coordinate must be separated by whitespace. The pose is defined relative to the plugin's parent element. So, if the plugin is used inside of a <model> tag, then the source's <pose> is relative to the model's pose. If the plugin is used inside of a <world> tag, then the source's <pose> is relative to the world (i.e., <pose> specifies an absolute pose). If no pose is specified, {0, 0, 0, 0, 0, 0} will be used.
  • <attenuation_function> The attenuation function. See logical_audio::AttenuationFunction for a list of valid attenuation functions, and logical_audio::SetAttenuationFunction for how to specify an attenuation function in SDF.
  • <attenuation_shape> The attenuation shape. See logical_audio::AttenuationShape for a list of valid attenuation shapes, and logical_audio::SetAttenuationShape for how to specify an attenuation shape in SDF.
  • <inner_radius> The inner radius of the attenuation shape. This value must be >= 0.0. The volume of the source will be <source><volume> at locations that have a distance <= inner radius from the source.
  • <falloff_distance> The falloff distance. This value must be greater than the value of the source's <inner_radius>. This defines the distance from the audio source where the volume becomes 0.
  • <volume_level> The volume level emitted from the source. This must be a value between 0.0 and 1.0 (representing 0% to 100%).
  • <playing> Whether the source should play immediately or not. Use true to initiate audio immediately, and false otherwise.
  • <play_duration> The duration (in seconds) audio is played from the source. This value must be an integer >= 0. A value of 0 means that the source will play for an infinite amount of time.

Specifying a microphone via SDF is done as follows:

<microphone> A new microphone in the environment, which has the following child elements:

  • <id> The microphone ID, which must be unique and an integer >= 0. An ID < 0 results in undefined behavior. The ID must be unique within the scope of all other microphone IDs in the plugin's parent element - so, if a microphone was created in a <model> with an ID of 1, no other microphones in the same model can have an ID of 1 (however, microphones that belong to other models can have an ID of 1).
  • <pose> The pose, expressed as "x y z roll pitch yaw". Each pose coordinate must be separated by whitespace. The pose is defined relative to the plugin's parent element. So, if the plugin is used inside of a <model> tag, then the source's <pose> is relative to the model's pose. If the plugin is used inside of a <world> tag, then the source's <pose> is relative to the world (i.e., <pose> specifies an absolute pose). If no pose is specified, {0, 0, 0, 0, 0, 0} will be used.
  • <volume_threshold> The minimum volume level the microphone can detect. This must be a value between 0.0 and 1.0 (representing 0% to 100%). If no volume threshold is specified, 0.0 will be used.

Sources can be started and stopped via Ignition service calls. If a source is successfully created, the following services will be created for the source (<PREFIX> is the scoped name for the source - see scopedName for more details - and <id> is the value specified in the source's <id> tag from the SDF):

  • <PREFIX>/source_<id>/play
    • Starts playing the source with the specified ID. If the source is already playing, nothing happens.
  • <PREFIX>/source_<id>/stop
    • Stops playing the source with the specified ID. If the source is already stopped, nothing happens.

Microphone detection information can be retrieved via Ignition topics. Whenever a microphone detects a source, it publishes a message to the <PREFIX>/mic_<id>/detection topic, where <PREFIX> is the scoped name for the microphone - see scopedName for more details - and <id> is the value specified in the microphone's <id> tag from the SDF.

Constructor & Destructor Documentation

◆ LogicalAudioSensorPlugin()

Constructor.

◆ ~LogicalAudioSensorPlugin()

~LogicalAudioSensorPlugin ( )
override

Destructor.

Member Function Documentation

◆ Configure()

void Configure ( const Entity _entity,
const std::shared_ptr< const sdf::Element > &  _sdf,
EntityComponentManager _ecm,
EventManager _eventMgr 
)
overridevirtual

Documentation inherited.

Implements ISystemConfigure.

◆ PostUpdate()

void PostUpdate ( const UpdateInfo _info,
const EntityComponentManager _ecm 
)
overridevirtual

Documentation inherited.

Implements ISystemPostUpdate.

◆ PreUpdate()

void PreUpdate ( const UpdateInfo _info,
EntityComponentManager _ecm 
)
overridevirtual

Implements ISystemPreUpdate.


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