Gazebo Sim

API Reference

7.9.0
AcousticComms Class Reference

A comms model that simulates communication using acoustic devices. The model uses simple distance based acoustics model. More...

#include <AcousticComms.hh>

Public Member Functions

 AcousticComms ()
 
void Load (const Entity &_entity, std::shared_ptr< const sdf::Element > _sdf, EntityComponentManager &_ecm, EventManager &_eventMgr) override
 This method is called when the system is being configured override this to load any additional params for the comms model. More...
 
void Step (const UpdateInfo &_info, const comms::Registry &_currentRegistry, comms::Registry &_newRegistry, EntityComponentManager &_ecm) override
 This method is called when there is a timestep in the simulator override this to update your data structures as needed. More...
 
- Public Member Functions inherited from ICommsModel
 ICommsModel ()
 Constructor. More...
 
void Configure (const Entity &_entity, const std::shared_ptr< const sdf::Element > &_sdf, EntityComponentManager &_ecm, EventManager &_eventMgr) override
 Configure the system. More...
 
void PreUpdate (const UpdateInfo &_info, EntityComponentManager &_ecm) override
 
virtual void StepImpl (const UpdateInfo &_info, EntityComponentManager &_ecm)
 This method is called when there is a timestep in the simulator. More...
 
- Public Member Functions inherited from System
 System ()=default
 Constructor. More...
 
virtual ~System ()=default
 Destructor. More...
 

Detailed Description

A comms model that simulates communication using acoustic devices. The model uses simple distance based acoustics model.

This system can be configured with the following SDF parameters:

  • Optional parameters:
    • <max_range>: Hard limit on range (meters). No communication will happen beyond this range. Default is 1000.
    • <speed_of_sound>: Speed of sound in the medium (meters/sec). Default is 343.0
    • <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'. 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. Defaults to zero.
    • <propagation_model> : Enables the use of propagation model. Disabled by default.
      • <source_power> : Source power at the transmitter in Watts. Defaults to 2 kW.
      • <noise_level> : Ratio of the noise intensity at the receiver to the same reference intensity used for source level. Defaults to 1.
      • <spectral_efficiency> : 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> : Seed value to be used for random sampling.

Here's an example: <plugin filename="gz-sim-acoustic-comms-system" name="systems::AcousticComms">

<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>

<propagation_model> <source_power>2000</source_power> <noise_level>1</noise_level> <spectral_efficiency>7</spectral_efficiency> </propagation_model>

</plugin>

Constructor & Destructor Documentation

◆ AcousticComms()

AcousticComms ( )
explicit

Member Function Documentation

◆ Load()

void Load ( const Entity _entity,
std::shared_ptr< const sdf::Element >  _sdf,
EntityComponentManager _ecm,
EventManager _eventMgr 
)
overridevirtual

This method is called when the system is being configured override this to load any additional params for the comms model.

Parameters
[in]_entityThe entity this plugin is attached to.
[in]_sdfThe SDF Element associated with this system plugin.
[in]_ecmThe EntityComponentManager of the given simulation instance.
[in]_eventMgrThe EventManager of the given simulation instance.

Implements ICommsModel.

◆ Step()

void Step ( const UpdateInfo _info,
const comms::Registry _currentRegistry,
comms::Registry _newRegistry,
EntityComponentManager _ecm 
)
overridevirtual

This method is called when there is a timestep in the simulator override this to update your data structures as needed.

Note: this is an experimental interface and might change in the future.

Parameters
[in]_infoSimulator information about the current timestep.
[in]_currentRegistryThe current registry.
[out]_newRegistryThe new registry. When Step() is finished this will become the new registry.
[in]_ecm- Gazebo Sim's ECM.

Implements ICommsModel.


The documentation for this class was generated from the following file: