-
Notifications
You must be signed in to change notification settings - Fork 262
/
LogicalAudioSensorPlugin.hh
165 lines (155 loc) · 7.63 KB
/
LogicalAudioSensorPlugin.hh
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
/*
* Copyright (C) 2020 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#ifndef IGNITION_GAZEBO_SYSTEMS_LOGICAL_AUDIO_SENSOR_PLUGIN_HH_
#define IGNITION_GAZEBO_SYSTEMS_LOGICAL_AUDIO_SENSOR_PLUGIN_HH_
#include <memory>
#include <ignition/gazebo/System.hh>
namespace ignition
{
namespace gazebo
{
// Inline bracket to help doxygen filtering.
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace systems
{
// Forward Declaration
class LogicalAudioSensorPluginPrivate;
/// \brief 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
/// ignition::gazebo::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 ignition::gazebo::scopedName for more details -
/// and <id> is the value specified in the microphone's <id> tag from the SDF.
class IGNITION_GAZEBO_VISIBLE LogicalAudioSensorPlugin :
public System,
public ISystemConfigure,
public ISystemPreUpdate,
public ISystemPostUpdate
{
/// \brief Constructor
public: LogicalAudioSensorPlugin();
/// \brief Destructor
public: ~LogicalAudioSensorPlugin() override;
/// Documentation inherited
public: void Configure(const Entity &_entity,
const std::shared_ptr<const sdf::Element> &_sdf,
EntityComponentManager &_ecm,
EventManager &_eventMgr) override;
// Documentation inherited
public: void PreUpdate(const ignition::gazebo::UpdateInfo &_info,
ignition::gazebo::EntityComponentManager &_ecm) override;
/// Documentation inherited
public: void PostUpdate(const UpdateInfo &_info,
const EntityComponentManager &_ecm) override;
/// \brief Private data pointer
private: std::unique_ptr<LogicalAudioSensorPluginPrivate> dataPtr;
};
}
}
}
}
#endif