Gazebo Gazebo

API Reference

6.16.0
include/gz/sim/components/LogicalAudio.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2020 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 #ifndef GZ_GAZEBO_COMPONENTS_LOGICALAUDIO_HH_
18 #define GZ_GAZEBO_COMPONENTS_LOGICALAUDIO_HH_
19 
20 #include <chrono>
21 #include <cstdint>
22 #include <istream>
23 #include <ostream>
24 #include <ratio>
25 
28 #include <gz/sim/config.hh>
29 
30 namespace ignition
31 {
32 namespace gazebo
33 {
34 // Inline bracket to help doxygen filtering.
35 inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
36 namespace logical_audio
37 {
42 
47 
51  struct Source
52  {
54  unsigned int id;
55 
58 
61 
63  double innerRadius;
64 
68 
72 
73  public: bool operator==(const Source &_source) const
74  {
75  return this->id == _source.id;
76  }
77 
78  public: bool operator!=(const Source &_source) const
79  {
80  return !(*this == _source);
81  }
82  };
83 
87  {
89  SourcePlayInfo() : startTime()
90  {
91  }
92 
94  bool playing{false};
95 
99 
101  std::chrono::steady_clock::duration startTime;
102 
103  public: bool operator==(const SourcePlayInfo &_sourcePlayInfo) const
104  {
105  return (this->playing == _sourcePlayInfo.playing) &&
106  (this->playDuration == _sourcePlayInfo.playDuration) &&
107  (this->startTime == _sourcePlayInfo.startTime);
108  }
109 
110  public: bool operator!=(const SourcePlayInfo &_sourcePlayInfo) const
111  {
112  return !(*this == _sourcePlayInfo);
113  }
114  };
115 
119  struct Microphone
120  {
122  unsigned int id;
123 
127 
128  public: bool operator==(const Microphone &_microphone) const
129  {
130  return this->id == _microphone.id;
131  }
132 
133  public: bool operator!=(const Microphone &_microphone) const
134  {
135  return !(*this == _microphone);
136  }
137  };
138 }
139 
140 namespace serializers
141 {
145  {
146  auto temp = static_cast<unsigned int>(_func);
147  _out << temp;
148  return _out;
149  }
150 
154  {
155  unsigned int temp = 0u;
156  if (_in >> temp)
157  _func = static_cast<logical_audio::AttenuationFunction>(temp);
158  return _in;
159  }
160 
163  const logical_audio::AttenuationShape &_shape)
164  {
165  auto temp = static_cast<unsigned int>(_shape);
166  _out << temp;
167  return _out;
168  }
169 
173  {
174  unsigned int temp = 0u;
175  if (_in >> temp)
176  _shape = static_cast<logical_audio::AttenuationShape>(temp);
177  return _in;
178  }
179 
182  const std::chrono::steady_clock::duration &_dur)
183  {
184  _out << std::chrono::duration_cast<std::chrono::nanoseconds>(
185  _dur).count();
186  return _out;
187  }
188 
191  std::chrono::steady_clock::duration &_dur)
192  {
193  int64_t time;
194  _in >> time;
196  return _in;
197  }
198 
201  {
206  public: static std::ostream &Serialize(std::ostream &_out,
207  const logical_audio::Source &_source)
208  {
209  _out << _source.id << " " << _source.attFunc << " " << _source.attShape
210  << " " << _source.innerRadius << " " << _source.falloffDistance
211  << " " << _source.emissionVolume;
212  return _out;
213  }
214 
219  public: static std::istream &Deserialize(std::istream &_in,
220  logical_audio::Source &_source)
221  {
222  _in >> _source.id >> _source.attFunc >> _source.attShape
223  >> _source.innerRadius >> _source.falloffDistance
224  >> _source.emissionVolume;
225  return _in;
226  }
227  };
228 
231  {
236  public: static std::ostream &Serialize(std::ostream &_out,
237  const logical_audio::SourcePlayInfo &_playInfo)
238  {
239  _out << _playInfo.playing << " " << _playInfo.playDuration.count() << " "
240  << _playInfo.startTime;
241  return _out;
242  }
243 
248  public: static std::istream &Deserialize(std::istream &_in,
250  {
251  uint64_t count;
252  _in >> _playInfo.playing >> count >> _playInfo.startTime;
253  _playInfo.playDuration = std::chrono::seconds(count);
254  return _in;
255  }
256  };
257 
260  {
265  public: static std::ostream &Serialize(std::ostream &_out,
266  const logical_audio::Microphone &_mic)
267  {
268  _out << _mic.id << " " << _mic.volumeDetectionThreshold;
269  return _out;
270  }
271 
275  public: static std::istream &Deserialize(std::istream &_in,
277  {
278  _in >> _mic.id >> _mic.volumeDetectionThreshold;
279  return _in;
280  }
281  };
282 }
283 
284 // using separate namespace blocks so all components appear in Doxygen
285 // (appears as if Doxygen can't parse multiple components in a single
286 // namespace block since IGN_GAZEBO_REGISTER_COMPONENT doesn't have a
287 // trailing semicolon)
288 namespace components
289 {
292  using LogicalAudioSource = Component<logical_audio::Source,
293  class LogicalAudioSourceTag,
294  serializers::LogicalAudioSourceSerializer>;
295  IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LogicalAudioSource",
296  LogicalAudioSource)
297 }
298 
299 namespace components
300 {
304  class LogicalAudioSourcePlayInfoTag,
305  serializers::LogicalAudioSourcePlayInfoSerializer>;
307  "ign_gazebo_components.LogicalAudioSourcePlayInfo",
308  LogicalAudioSourcePlayInfo)
309 }
310 
311 namespace components
312 {
316  class LogicalMicrophoneTag,
317  serializers::LogicalMicrophoneSerializer>;
318  IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LogicalMicrophone",
319  LogicalMicrophone)
320 }
321 }
322 }
323 }
324 
325 #endif
bool operator!=(const SourcePlayInfo &_sourcePlayInfo) const
Definition: include/gz/sim/components/LogicalAudio.hh:110
logical_audio::AttenuationFunction attFunc
The source's attenuation function.
Definition: include/gz/sim/components/LogicalAudio.hh:57
This library is part of the Gazebo project.
#define IGN_GAZEBO_REGISTER_COMPONENT(_compType, _classname)
Static component registration macro.
Definition: gz/sim/components/Factory.hh:509
std::istream & operator>>(std::istream &_in, logical_audio::AttenuationFunction &_func)
Input stream overload for logical_audio::AttenuationFunction.
Definition: include/gz/sim/components/LogicalAudio.hh:152
std::chrono::seconds playDuration
How long the source should play for, in seconds. Setting this to 0 means the source has a play durati...
Definition: include/gz/sim/components/LogicalAudio.hh:98
Properties of a logical audio source. A source also has a pose, which can be stored as a component of...
Definition: include/gz/sim/components/LogicalAudio.hh:51
static std::ostream & Serialize(std::ostream &_out, const logical_audio::Source &_source)
Serialization for logical_audio::Source.
Definition: include/gz/sim/components/LogicalAudio.hh:206
logical_audio::AttenuationShape attShape
The source's attenuation shape.
Definition: include/gz/sim/components/LogicalAudio.hh:60
double innerRadius
The source's inner radius, which should be >= 0.
Definition: include/gz/sim/components/LogicalAudio.hh:63
std::chrono::steady_clock::duration startTime
The time at which the source most recently started playing.
Definition: include/gz/sim/components/LogicalAudio.hh:101
std::istream & operator>>(std::istream &_in, std::chrono::steady_clock::duration &_dur)
Input stream overload for std::chrono::steady_clock::duration.
Definition: include/gz/sim/components/LogicalAudio.hh:190
bool operator==(const Microphone &_microphone) const
Definition: include/gz/sim/components/LogicalAudio.hh:128
static std::ostream & Serialize(std::ostream &_out, const logical_audio::SourcePlayInfo &_playInfo)
Serialization for logical_audio::SourcePlayInfo.
Definition: include/gz/sim/components/LogicalAudio.hh:236
static std::istream & Deserialize(std::istream &_in, logical_audio::Source &_source)
Deserialization for logical_audio::Source.
Definition: include/gz/sim/components/LogicalAudio.hh:219
static std::ostream & Serialize(std::ostream &_out, const logical_audio::Microphone &_mic)
Serialization for logical_audio::Microphone.
Definition: include/gz/sim/components/LogicalAudio.hh:265
Serializer for components::LogicalAudioSourcePlayInfo object.
Definition: include/gz/sim/components/LogicalAudio.hh:230
STL class.
static std::istream & Deserialize(std::istream &_in, logical_audio::SourcePlayInfo &_playInfo)
Deserialization for logical_audio::SourcePlayInfo.
Definition: include/gz/sim/components/LogicalAudio.hh:248
IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Actor", Actor) using AnimationTime
Time in seconds within animation being currently played.
bool operator==(const SourcePlayInfo &_sourcePlayInfo) const
Definition: include/gz/sim/components/LogicalAudio.hh:103
std::ostream & operator<<(std::ostream &_out, const logical_audio::AttenuationFunction &_func)
Output stream overload for logical_audio::AttenuationFunction.
Definition: include/gz/sim/components/LogicalAudio.hh:143
unsigned int id
The microphone's id.
Definition: include/gz/sim/components/LogicalAudio.hh:122
AttenuationShape
Audio source attenuation shapes. AttenuationShape::Undefined is used to indicate that an attenuation ...
Definition: include/gz/sim/components/LogicalAudio.hh:46
AttenuationFunction
Audio source attenuation functions. AttenuationFunction::Undefined is used to indicate that an attenu...
Definition: include/gz/sim/components/LogicalAudio.hh:41
Serializer for components::LogicalAudioSource object.
Definition: include/gz/sim/components/LogicalAudio.hh:200
bool operator!=(const Microphone &_microphone) const
Definition: include/gz/sim/components/LogicalAudio.hh:133
A component type that wraps any data type. The intention is for this class to be used to create simpl...
Definition: gz/sim/components/Component.hh:324
SourcePlayInfo()
Constructor.
Definition: include/gz/sim/components/LogicalAudio.hh:89
double volumeDetectionThreshold
The minimum volume this microphone can detect. This should be a value between 0.0 (0% volume) and 1....
Definition: include/gz/sim/components/LogicalAudio.hh:126
std::ostream & operator<<(std::ostream &_out, const std::chrono::steady_clock::duration &_dur)
Output stream overload for std::chrono::steady_clock::duration.
Definition: include/gz/sim/components/LogicalAudio.hh:181
A source's playing information. Useful for keeping track of when to start/stop playing a source.
Definition: include/gz/sim/components/LogicalAudio.hh:86
bool operator!=(const Source &_source) const
Definition: include/gz/sim/components/LogicalAudio.hh:78
static std::istream & Deserialize(std::istream &_in, logical_audio::Microphone &_mic)
Deserialization for logical_audio::Microphone.
Definition: include/gz/sim/components/LogicalAudio.hh:275
T count(T... args)
double falloffDistance
The source's falloff distance, which should be greater than Source::innerRadius.
Definition: include/gz/sim/components/LogicalAudio.hh:67
double emissionVolume
The source's emission volume, which should be between 0.0 (0% volume) and 1.0 (100% volume)
Definition: include/gz/sim/components/LogicalAudio.hh:71
bool playing
Whether the source is currently playing or not.
Definition: include/gz/sim/components/LogicalAudio.hh:94
bool operator==(const Source &_source) const
Definition: include/gz/sim/components/LogicalAudio.hh:73
STL class.
Component< logical_audio::Source, class LogicalAudioSourceTag, serializers::LogicalAudioSourceSerializer > LogicalAudioSource
A component that contains a logical audio source, which is represented by logical_audio::Source.
Definition: include/gz/sim/components/LogicalAudio.hh:294
Properties of a logical audio microphone. A microphone also has a pose, which can be stored as a comp...
Definition: include/gz/sim/components/LogicalAudio.hh:119
Serializer for components::LogicalMicrophone object.
Definition: include/gz/sim/components/LogicalAudio.hh:259
unsigned int id
The source's id.
Definition: include/gz/sim/components/LogicalAudio.hh:54