Gazebo Gazebo

API Reference

3.15.2
src/systems/logical_audio_sensor_plugin/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_SYSTEMS_LOGICAL_AUDIO_SENSOR_PLUGIN_LOGICALAUDIO_HH_
18 #define GZ_GAZEBO_SYSTEMS_LOGICAL_AUDIO_SENSOR_PLUGIN_LOGICALAUDIO_HH_
19 
20 #include <string>
21 
23 #include <gz/sim/config.hh>
24 #include <gz/math/Pose3.hh>
25 
26 namespace ignition
27 {
28 namespace gazebo
29 {
30 // Inline bracket to help doxygen filtering.
31 inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
32 namespace logical_audio
33 {
44  bool detect(double _volumeLevel, double _volumeDetectionThreshold);
45 
64  double computeVolume(bool _playing,
65  AttenuationFunction _attenuationFunc,
66  AttenuationShape _attenuationShape,
67  double _sourceEmissionVolume,
68  double _innerRadius,
69  double _falloffDistance,
70  const gz::math::Pose3d &_sourcePose,
71  const gz::math::Pose3d &_targetPose);
72 
86  void setAttenuationFunction(AttenuationFunction &_attenuationFunc,
87  std::string _str);
88 
101  void setAttenuationShape(AttenuationShape &_attenuationShape,
102  std::string _str);
103 
113  void validateInnerRadiusAndFalloffDistance(double &_innerRadius,
114  double &_falloffDistance);
115 
120  void validateVolumeLevel(double &_volumeLevel);
121 }
122 }
123 }
124 }
125 
126 #endif
This library is part of the Ignition Robotics project.
STL class.
void setAttenuationFunction(AttenuationFunction &_attenuationFunc, std::string _str)
Set the attenuation function that matches the defined string. The string is not case sensitive,...
void setAttenuationShape(AttenuationShape &_attenuationShape, std::string _str)
Set the attenuation shape that matches the defined string. The string is not case sensitive,...
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
bool detect(double _volumeLevel, double _volumeDetectionThreshold)
Determines if an audio device can detect volume at a certain level.
void validateVolumeLevel(double &_volumeLevel)
Validate a source's emission volume level.
void validateInnerRadiusAndFalloffDistance(double &_innerRadius, double &_falloffDistance)
Validate the inner radius and falloff distance for an audio source.
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.