Gazebo Gazebo

API Reference

6.16.0
ICommsModel Class Referenceabstract

Abstract interface to define how the environment should handle communication simulation. As an example, this class could be responsible for handling dropouts, decay and packet collisions. More...

#include <ICommsModel.hh>

Public Member Functions

 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...
 
virtual void Load (const Entity &_entity, std::shared_ptr< const sdf::Element > _sdf, EntityComponentManager &_ecm, EventManager &_eventMgr)=0
 This method is called when the system is being configured override this to load any additional params for the comms model. More...
 
void PreUpdate (const ignition::gazebo::UpdateInfo &_info, ignition::gazebo::EntityComponentManager &_ecm) override
 
virtual void Step (const UpdateInfo &_info, const Registry &_currentRegistry, Registry &_newRegistry, EntityComponentManager &_ecm)=0
 This method is called when there is a timestep in the simulator override this to update your data structures as needed. More...
 
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

Abstract interface to define how the environment should handle communication simulation. As an example, this class could be responsible for handling dropouts, decay and packet collisions.

The derived comms models can be configured with the following SDF parameters:

  • Optional parameters: <step_size> If defined this will allow the comms model to run at a higher frequency than the physics engine. This is useful when dealing with ranging. If the <step_size> is set larger than the physics engine dt then the comms model step size will default to dt. Note: for consistency it is adviced that the dt is a multiple of timestep. Units are in seconds.

Here's an example: <physics name="1ms" type="ignored"> <max_step_size>2</max_step_size> <real_time_factor>1.0</real_time_factor> </physics> <plugin filename="ignition-gazebo-perfect-comms-system" name="ignition::gazebo::systems::PerfectComms"> <step_size>1</step_size> </plugin>

Constructor & Destructor Documentation

◆ ICommsModel()

ICommsModel ( )
explicit

Constructor.

Member Function Documentation

◆ Configure()

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

Configure the system.

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

◆ Load()

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

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.

Implemented in RFComms, and PerfectComms.

◆ PreUpdate()

void PreUpdate ( const ignition::gazebo::UpdateInfo _info,
ignition::gazebo::EntityComponentManager _ecm 
)
overridevirtual

Implements ISystemPreUpdate.

◆ Step()

virtual void Step ( const UpdateInfo _info,
const Registry _currentRegistry,
Registry _newRegistry,
EntityComponentManager _ecm 
)
pure virtual

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- Ignition's ECM.

Implemented in RFComms, and PerfectComms.

◆ StepImpl()

virtual void StepImpl ( const UpdateInfo _info,
EntityComponentManager _ecm 
)
virtual

This method is called when there is a timestep in the simulator.

Parameters
[in]_infoSimulator information about the current timestep. will become the new registry.
[in]_ecm- Ignition's ECM.

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