diff --git a/examples/worlds/acoustic_comms_propagation.sdf b/examples/worlds/acoustic_comms_propagation.sdf new file mode 100644 index 0000000000..7ccde3ad2d --- /dev/null +++ b/examples/worlds/acoustic_comms_propagation.sdf @@ -0,0 +1,264 @@ + + + + + + + 0.001 + 1.0 + + + + + + + + + 6 + 1400 + + + + + 0.001 + 150 + 7 + 0 + + + + + + true + 0 0 10 0 0 0 + 1 1 1 1 + 0.5 0.5 0.5 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + true + + + + + 0 0 1 + 100 100 + + + + + + + 0 0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + 2 0 0.5 0 0 0 + + + + 0.16666 + 0 + 0 + 0.16666 + 0 + 0.16666 + + 1.0 + + + + + 1 1 1 + + + + + + + + 1 1 1 + + + + 1 0 0 1 + 1 0 0 1 + 1 0 0 1 + + + + + +
addr1
+ addr1/rx +
+
+ + + -2 0 0.5 0 0 0 + + + + 0.16666 + 0 + 0 + 0.16666 + 0 + 0.16666 + + 1.0 + + + + + 1 1 1 + + + + + + + + 1 1 1 + + + + 0 0 1 1 + 0 0 1 1 + 0 0 1 1 + + + + + +
addr2
+ addr2/rx + + /broker/bind + /broker/unbind + +
+ +
+ + + 5 0 0.5 0 0 0 + + + + 0.16666 + 0 + 0 + 0.16666 + 0 + 0.16666 + + 1.0 + + + + + 1 1 1 + + + + + + + + 1 1 1 + + + + 1 0 0 1 + 1 0 0 1 + 1 0 0 1 + + + + + +
addr3
+ addr3/rx +
+
+ + + -5 0 0.5 0 0 0 + + + + 0.16666 + 0 + 0 + 0.16666 + 0 + 0.16666 + + 1.0 + + + + + 1 1 1 + + + + + + + + 1 1 1 + + + + 1 0 0 1 + 1 0 0 1 + 1 0 0 1 + + + + + +
addr4
+ addr4/rx +
+
+ +
+
diff --git a/src/systems/acoustic_comms/AcousticComms.cc b/src/systems/acoustic_comms/AcousticComms.cc index 93699fdd70..f11f56821e 100644 --- a/src/systems/acoustic_comms/AcousticComms.cc +++ b/src/systems/acoustic_comms/AcousticComms.cc @@ -61,8 +61,78 @@ class AcousticComms::Implementation std::tuple, std::chrono::duration>> lastMsgReceivedInfo; + + /// \brief This method simulates the propagation model, + /// and returns false if the packet was dropped, otherwise true. + public: bool propagationModel(double _distToSource, + 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 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; + + /// \brief Seed value for random sampling. + public: unsigned int seed = 0; }; +////////////////////////////////////////////////// +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. + + // The constant 170.8 comes from reference intensity measured + // 1m from the source. + double sl = 170.8 + 10 * std::log10(this->sourcePower); + double tl = 20 * std::log10(_distToSource); + + // Calculate SNR. + auto snr = sl - tl - this->noiseLevel; + + // 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(_numBytes) * + std::log(1 - ber)); + + gz::math::Rand::Seed(this->seed); + double randDraw = gz::math::Rand::DblUniform(); + return randDraw > packetDropProb; +} + ////////////////////////////////////////////////// AcousticComms::AcousticComms() : dataPtr(gz::utils::MakeUniqueImpl()) @@ -90,6 +160,18 @@ void AcousticComms::Load( _sdf->Get("collision_time_per_byte"); } + if (_sdf->HasElement("propagation_model")) + { + this->dataPtr->usePropagationModel = true; + sdf::ElementPtr propElement = _sdf->Clone()-> + GetElement("propagation_model"); + this->dataPtr->sourcePower = propElement->Get("source_power"); + this->dataPtr->noiseLevel = propElement->Get("noise_level"); + this->dataPtr->spectralEfficiency = + propElement->Get("spectral_efficiency"); + this->dataPtr->seed = propElement->Get("seed"); + } + gzmsg << "AcousticComms configured with max range : " << this->dataPtr->maxRange << " m and speed of sound : " << this->dataPtr->speedOfSound << " m/s." << std::endl; @@ -222,6 +304,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. diff --git a/src/systems/acoustic_comms/AcousticComms.hh b/src/systems/acoustic_comms/AcousticComms.hh index f443e3970c..2845436cef 100644 --- a/src/systems/acoustic_comms/AcousticComms.hh +++ b/src/systems/acoustic_comms/AcousticComms.hh @@ -28,6 +28,7 @@ #include #include +#include #include "gz/sim/comms/ICommsModel.hh" #include #include @@ -55,19 +56,42 @@ namespace systems /// * : 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. /// * : 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. + /// * : Enables the use of propagation model. + /// Disabled by default. + /// * : Source power at the transmitter in Watts. + /// Defaults to 2 kW. + /// * : Ratio of the noise intensity at the + /// receiver to the same reference intensity used + /// for source level. Defaults to 1. + /// * : Information rate that can be transmitted + /// over a given bandwidth in a specific + /// communication system, in (bits/sec)/Hz. + /// Defaults to 7 bits/sec/Hz. + /// * : Seed value to be used for random sampling. /// /// Here's an example: /// - /// 6 + /// + /// 500 /// 1400 + /// /// 0.001 /// 0.001 + /// + /// + /// 2000 + /// 1 + /// 7 + /// + /// /// class AcousticComms: diff --git a/test/integration/acoustic_comms.cc b/test/integration/acoustic_comms.cc index a0d0c4e930..cb4a447ee6 100644 --- a/test/integration/acoustic_comms.cc +++ b/test/integration/acoustic_comms.cc @@ -161,6 +161,10 @@ INSTANTIATE_TEST_SUITE_P( // Message packets will be dropped as they are sent too fast // compared to "collision_time_interval". AcousticCommsTestDefinition( - "acoustic_comms_packet_collision.sdf", "addr2", "addr1", 3, 1) + "acoustic_comms_packet_collision.sdf", "addr2", "addr1", 3, 1), + // Source power is decreased and noise bumped up to make the packets + // drop. + AcousticCommsTestDefinition( + "acoustic_comms_propagation.sdf", "addr2", "addr1", 3, 0) ) );