A comms model that simulates communication using radio frequency (RF) devices. The model uses a log-distance path loss function. More...
#include <RFComms.hh>
Public Member Functions | |
RFComms () | |
Constructor. More... | |
~RFComms () override=default | |
Destructor. More... | |
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 ignition::gazebo::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 ignition::gazebo::UpdateInfo &_info, ignition::gazebo::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 radio frequency (RF) devices. The model uses a log-distance path loss function.
This communication model has been ported from: https://github.com/osrf/subt .
This system can be configured with the following SDF parameters:
- Optional parameters: <range_config> Element used to capture the range configuration based on a log-normal distribution. This block can contain any of the next parameters:
- <max_range>: Hard limit on range (meters). No communication will happen beyond this range. Default is 50.
- <fading_exponent>: Fading exponent used in the normal distribution. Default is 2.5.
- <l0>: Path loss at the reference distance (1 meter) in dBm. Default is 40.
- <sigma>: Standard deviation of the normal distribution. Default is 10.
<radio_config> Element used to capture the radio configuration. This block can contain any of the next parameters:
- <capacity>: Capacity of radio in bits-per-second. Default is 54000000 (54 Mbps).
- <tx_power>: Transmitter power in dBm. Default is 27dBm (500mW).
- <noise_floor>: Noise floor in dBm. Default is -90dBm.
- <modulation>: Supported modulations: ["QPSK"]. Default is "QPSK".
Here's an example: <plugin filename="ignition-gazebo-rf-comms-system" name="ignition::gazebo::systems::RFComms"> <range_config> <max_range>500000.0</max_range> <fading_exponent>1.5</fading_exponent> <l0>40</l0> <sigma>10.0</sigma> </range_config> <radio_config> <capacity>1000000</capacity> <tx_power>20</tx_power> <noise_floor>-90</noise_floor> <modulation>QPSK</modulation> </radio_config> </plugin>
Constructor & Destructor Documentation
◆ RFComms()
|
explicit |
Constructor.
◆ ~RFComms()
|
overridedefault |
Destructor.
Member Function Documentation
◆ Load()
|
overridevirtual |
This method is called when the system is being configured override this to load any additional params for the comms model.
- Parameters
-
[in] _entity The entity this plugin is attached to. [in] _sdf The SDF Element associated with this system plugin. [in] _ecm The EntityComponentManager of the given simulation instance. [in] _eventMgr The EventManager of the given simulation instance.
Implements ICommsModel.
◆ Step()
|
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] _info Simulator information about the current timestep. [in] _currentRegistry The current registry. [out] _newRegistry The new registry. When Step() is finished this will become the new registry. [in] _ecm - Ignition's ECM.
Implements ICommsModel.
The documentation for this class was generated from the following file: