PerfectComms Class Reference
An example of a comms model. This model always delivers any message to its destination. More...
#include <PerfectComms.hh>
Public Member Functions | |
| PerfectComms () | |
| Constructor.   | |
| 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.   | |
| 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.   | |
  Public Member Functions inherited from ICommsModel | |
| ICommsModel () | |
| Constructor.   | |
| void | Configure (const Entity &_entity, const std::shared_ptr< const sdf::Element > &_sdf, EntityComponentManager &_ecm, EventManager &_eventMgr) override | 
| Configure the system.   | |
| 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.   | |
  Public Member Functions inherited from System | |
| System ()=default | |
| Constructor.   | |
| virtual | ~System ()=default | 
| Destructor.   | |
Additional Inherited Members | |
  Public Types inherited from System | |
| using | PriorityType = int32_t | 
| Signed integer type used for specifying priority of the execution order of PreUpdate and Update phases.   | |
  Static Public Attributes inherited from System | |
| static constexpr PriorityType | kDefaultPriority = {0} | 
| Default priority value for execution order of the PreUpdate and Update phases.   | |
| static constexpr std::string_view | kPriorityElementName | 
| Name of the XML element from which the priority value will be parsed.   | |
Detailed Description
An example of a comms model. This model always delivers any message to its destination.
Constructor & Destructor Documentation
◆ PerfectComms()
      
  | 
  explicit | 
Constructor.
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 - Gazebo Sim's ECM.  
Implements ICommsModel.
The documentation for this class was generated from the following file:
 Public Member Functions inherited from