Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Acoustic comms : Propagation model #1793

Merged
merged 9 commits into from
Nov 17, 2022
Merged
Show file tree
Hide file tree
Changes from 3 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
90 changes: 90 additions & 0 deletions src/systems/acoustic_comms/AcousticComms.cc
Original file line number Diff line number Diff line change
Expand Up @@ -61,8 +61,76 @@ class AcousticComms::Implementation
std::tuple<std::chrono::duration<double>,
std::chrono::duration<double>>>
lastMsgReceivedInfo;

public: bool propagationModel(double _distToSource,
adityapande-1995 marked this conversation as resolved.
Show resolved Hide resolved
int _numBytes);

/// \brief Source power in Watts.
/// \ref https://www.sciencedirect.com/topics/
/// computer-science/underwater-acoustic-signal
public: double sourcePower = 2000;

/// \brief Ratio of the noise intensity at the
/// receiver to the same reference intensity used for source level.
public: double noiseLevel = 1;

/// \brief Ratio of the total noise power at the array to the
/// noise received by the array along its main response axis.
/// \ref https://ieeexplore.ieee.org/document/5664178
public: double directivityIndex = 4;

/// \brief Information rate that can be transmitted over a given
/// bandwidth in a specific communication system, in (bits/sec)/Hz.
/// \ref: https://www.ncbi.nlm.nih.gov/pmc/articles/PMC5514747/
public: double spectralEfficiency = 7.0;

/// \brief Flag to store if the propagation model should be used.
public: bool usePropagationModel = false;
};

//////////////////////////////////////////////////
bool AcousticComms::Implementation::propagationModel(
double _distToSource,
int _numBytes
)
{
// From https://www.mathworks.com/help/phased/ug/sonar-equation.html
// SNR = SL - TL - (NL - DI)
// SNR : Signal to noise ratio.
// SL : Source level. Ratio of the transmitted intensity from
// the source to a reference intensity (1 m from source),
// converted to dB.
// TL : Transmission loss (dB)
// NL : Noise level.
// DI : Receiver directivity index.

double sl = 171.5 + 10 * std::log10(this->sourcePower);
adityapande-1995 marked this conversation as resolved.
Show resolved Hide resolved
double tl = 20 * std::log10(_distToSource);

// Calculate SNR.
auto snr = sl - tl - (this->noiseLevel - this->directivityIndex);
adityapande-1995 marked this conversation as resolved.
Show resolved Hide resolved

// References : https://www.montana.edu/aolson/ee447/EB%20and%20NO.pdf
// https://en.wikipedia.org/wiki/Eb/N0
auto EbByN0 = snr / this->spectralEfficiency;

// Bit error rate calculation using BPSK.
// Reference : https://www.gaussianwaves.com/2012/07/
// intuitive-derivation-of-performance-of-an-optimum-
// bpsk-receiver-in-awgn-channel/
// Reference : https://unetstack.net/handbook/unet-handbook_modems
// _and_channel_models.html
auto ber = 0.5 * std::erfc(EbByN0);

// Calculate if the packet was dropped.
double packetDropProb =
1.0 - std::exp(static_cast<double>(_numBytes) *
std::log(1 - ber));

double randDraw = gz::math::Rand::DblUniform();
return randDraw > packetDropProb;
}

//////////////////////////////////////////////////
AcousticComms::AcousticComms()
: dataPtr(gz::utils::MakeUniqueImpl<Implementation>())
Expand Down Expand Up @@ -90,6 +158,19 @@ void AcousticComms::Load(
_sdf->Get<double>("collision_time_per_byte");
}

if (_sdf->HasElement("propagation_model"))
{
this->dataPtr->usePropagationModel = true;
sdf::ElementPtr propElement = _sdf->Clone()->
GetElement("propagation_model");
Comment on lines +166 to +167
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Open to suggestions on how cloning can be avoided here. GetElement cannot be applied to const Element members it seems, and _sdf->GetElement("foo") throws an error that " this argument discards qualifiers."

Copy link
Contributor

@arjo129 arjo129 Nov 15, 2022

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Typically, I use GetFirstElement and then iterate. It's not ideal and very counter intuitive that a Get* method is non-const. You don't have to do this. I don't see this clone as very expensive.

this->dataPtr->sourcePower = propElement->Get<double>("source_power");
this->dataPtr->noiseLevel = propElement->Get<double>("noise_level");
this->dataPtr->directivityIndex =
propElement->Get<double>("directivity_index");
this->dataPtr->spectralEfficiency =
propElement->Get<double>("spectral_efficiency");
}

gzmsg << "AcousticComms configured with max range : " <<
this->dataPtr->maxRange << " m and speed of sound : " <<
this->dataPtr->speedOfSound << " m/s." << std::endl;
Expand Down Expand Up @@ -222,6 +303,15 @@ void AcousticComms::Step(
receivedSuccessfully = true;
}

// Packet has survived collisions, check if the propagation model
// should be run on this packet.
if (this->dataPtr->usePropagationModel)
{
receivedSuccessfully = receivedSuccessfully &&
this->dataPtr->propagationModel(distanceCoveredByMessage,
msg->data().length());
}

// This message needs to be processed.
// Push the msg to inbound of the destination if
// receivedSuccessfully is true, else it is dropped.
Expand Down
9 changes: 6 additions & 3 deletions src/systems/acoustic_comms/AcousticComms.hh
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
#include <unordered_map>

#include <sdf/sdf.hh>
#include <gz/math/Rand.hh>
#include "gz/sim/comms/ICommsModel.hh"
#include <gz/sim/System.hh>
#include <gz/sim/Entity.hh>
Expand Down Expand Up @@ -55,16 +56,18 @@ namespace systems
/// * <collision_time_per_byte> : If a subscriber receives a message
/// 'b' bytes long at time 't0', it won't receive
/// and other message till time :
/// 't0 + b * collision_time_per_byte'
/// 't0 + b * collision_time_per_byte'.
/// Defaults to zero.
/// * <collision_time_packet_drop> : If a packet is dropped at time
/// `t0`, the next packet won't be received until
/// time `t0 + collision_time_packet_drop`
/// time `t0 + collision_time_packet_drop`.
/// Defaults to zero.
///
/// Here's an example:
/// <plugin
/// filename="gz-sim-acoustic-comms-system"
/// name="gz::sim::systems::AcousticComms">
/// <max_range>6</max_range>
/// <max_range>500</max_range>
/// <speed_of_sound>1400</speed_of_sound>
/// <collision_time_per_byte>0.001</collision_time_per_byte>
/// <collision_time_packet_drop>0.001</collision_time_packet_drop>
Expand Down