EventForwarder.cpp
Go to the documentation of this file.
4 
5 using namespace swarmros;
6 using namespace swarmros::bridge;
7 
8 EventForwarder::EventForwarder(ros::NodeHandle& nodeHandle, const std::string& source, const std::string& message, swarmio::Endpoint* endpoint)
9  : _endpoint(endpoint)
10 {
11  // Register schema
12  const auto& serializer = introspection::MessageSerializer::MessageSerializerForType(message, "swarmros");
13 
14  // Save message type
15  _message = serializer.GetFullName();
16 
17  // Check message format
18  if (!EventMessage::IsEventSerializer(serializer))
19  {
20  throw MessageMismatchException("Message type has no valid event header", source, "swarmros/EventHeader", _message);
21  }
22 
23  // Subscribe
24  _subscriber = nodeHandle.subscribe<EventMessage>(source, 1, &EventForwarder::EventReceived, this);
25 }
26 
28 {
29  if (message->GetType() == _message)
30  {
31  // Prepare notification
32  swarmio::data::event::Notification notification;
33  notification.set_name(message->GetName());
34  notification.mutable_parameters()->insert(message->GetParameters().pairs().begin(), message->GetParameters().pairs().end());
35 
36  // Send message
37  if (message->GetNode().empty())
38  {
40  }
41  else
42  {
43  auto node = _endpoint->NodeForUUID(message->GetNode());
45  }
46  }
47  else
48  {
49  throw MessageMismatchException("Invalid message type received from topic", _subscriber.getTopic(), _message, message->GetType());
50  }
51 }
EventForwarder(ros::NodeHandle &nodeHandle, const std::string &source, const std::string &message, swarmio::Endpoint *endpoint)
Construct a new EventForwarder object.
static void Trigger(Endpoint *endpoint, const data::event::Notification &event)
Trigger an event globally.
virtual const Node * NodeForUUID(const std::string &uuid)=0
Retreive a node by its UUID.
ros::Subscriber _subscriber
ROS topic subscriber.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void EventReceived(const EventMessage::ConstPtr &message)
Called whenever the topic is updated.
swarmio::Endpoint * _endpoint
Telemetry service.
static const MessageSerializer & MessageSerializerForType(const std::string &type, const std::string &parentPackage)
Look up or build a reader for a message type.
std::string _message
Message type.
EventMessage implements an interface with the ROS type system to send and receive events...
Definition: EventMessage.h:15
std::string getTopic() const
Abstract base class for Endpoint implementations.
Definition: Endpoint.h:25
static bool IsEventSerializer(const introspection::MessageSerializer &serializer)
Checks whether a serializer has the correct layout.
Definition: EventMessage.h:39
Exception thrown when the expected type of a message does not match the actual type.


swarmros
Author(s):
autogenerated on Fri Apr 3 2020 03:42:48