A Handler implementation that publishes events from the swarm to a ROS topic. More...
#include <EventPublisher.h>

Public Member Functions | |
| virtual swarmio::data::discovery::Schema | DescribeEvent (const std::string &name) override |
| Describe the event based on the configuration of this instance. More... | |
| EventPublisher (ros::NodeHandle &nodeHandle, const std::string &suffix, const std::string &message, swarmio::services::event::Service &eventService, const std::string &name) | |
| Construct a new EventPublisher object. More... | |
| virtual void | EventWasTriggered (const swarmio::Node *node, const swarmio::data::event::Notification &event) override |
| Publish the event in the ROS topic. More... | |
| virtual | ~EventPublisher () override |
| Destructor. More... | |
Public Member Functions inherited from swarmros::bridge::Pylon | |
| virtual | ~Pylon () |
| Add virtual destructor. More... | |
Public Member Functions inherited from swarmio::services::event::Handler | |
| virtual void | EventWasTriggered (const Node *node, const data::event::Notification &event)=0 |
| Handlers are notified using this method when an event has been triggered. More... | |
Private Attributes | |
| swarmio::services::event::Service & | _eventService |
| Event service. More... | |
| std::string | _name |
| Event name. More... | |
| ros::Publisher | _publisher |
| Publisher. More... | |
| const introspection::MessageSerializer * | _serializer |
| Event name. More... | |
Additional Inherited Members | |
Protected Member Functions inherited from swarmros::bridge::Pylon | |
| Pylon () | |
| Mark as abstract. More... | |
A Handler implementation that publishes events from the swarm to a ROS topic.
Definition at line 17 of file EventPublisher.h.
| EventPublisher::EventPublisher | ( | ros::NodeHandle & | nodeHandle, |
| const std::string & | suffix, | ||
| const std::string & | message, | ||
| swarmio::services::event::Service & | eventService, | ||
| const std::string & | name | ||
| ) |
Construct a new EventPublisher object.
| nodeHandle | Node handle |
| message | Event message tyoe |
| eventService | Event service |
| name | Event name |
Definition at line 7 of file EventPublisher.cpp.
|
overridevirtual |
Destructor.
Definition at line 67 of file EventPublisher.cpp.
|
overridevirtual |
Describe the event based on the configuration of this instance.
| name | Event name |
Implements swarmio::services::event::Handler.
Definition at line 55 of file EventPublisher.cpp.
|
overridevirtual |
Publish the event in the ROS topic.
| node | Source nodel |
| event | Event |
Definition at line 30 of file EventPublisher.cpp.
|
private |
Event service.
Definition at line 43 of file EventPublisher.h.
|
private |
Event name.
Definition at line 31 of file EventPublisher.h.
|
private |
Publisher.
Definition at line 25 of file EventPublisher.h.
|
private |
Event name.
Definition at line 37 of file EventPublisher.h.