example/Node.cpp
Go to the documentation of this file.
2 #include <swarmros/ExampleComplexMessage.h>
3 #include <chrono>
4 #include <iostream>
5 
6 using namespace swarmros;
7 using namespace swarmros::example;
8 
9 Node::Node(const std::string& name)
10  : _handle(name), _shutdownRequested(false), _reportInterval(50), _heartbeatCounter(0)
11 {
12  // Add event sources
13  _pongEventSource = _handle.advertise<SimpleEvent>("events/pong", 64, false);
14  _heartbeatEventSource = _handle.advertise<SimpleEvent>("events/heartbeat", 64, false);
15  _exampleEventSource = _handle.advertise<ExampleEvent>("events/report", 64, false);
16 
17  // Publish current counter value as telemetry
18  _heartbeatCounterTelemetryPublisher = _handle.advertise<UInt>("telemetry/heartbeatCounter", 1, true);
19 
20  // Publish a complex message that will be filled with gibberish every time a new report is published
21  _complexMessageTelemetryPublisher = _handle.advertise<ExampleComplexMessage>("telemetry/exampleComplexMessage", 1, true);
22 
23  // Add event sinks
24  _pingEventSink = _handle.subscribe("/bridge/events/ping", 64, &Node::HandleSimpleEvent, this);
25  _heartbeatEventSink = _handle.subscribe("/bridge/events/heartbeat", 64, &Node::HandleSimpleEvent, this);
26  _exampleEventSink = _handle.subscribe("/bridge/events/report", 64, &Node::HandleExampleEvent, this);
27 
28  // Subscribe to parameter
29  _reportIntervalParameterSubscriber = _handle.subscribe("/bridge/parameters/reportInterval", 1, &Node::HandleIntervalParameterChange, this);
30 
31  // Start worker thread
32  _worker = std::thread(&Node::Worker, this);
33 }
34 
36 {
37  for (uint64_t tick = 1; !_shutdownRequested; ++tick)
38  {
39  // Publish heartbeat event
40  SimpleEvent heartbeatEvent;
41  heartbeatEvent.eventHeader.name = "heartbeat";
42  _heartbeatEventSource.publish(heartbeatEvent);
43 
44  // Every interval, report current counter value
45  if (tick >= _reportInterval && _reportInterval != 0)
46  {
47  // Send report
48  ExampleEvent exampleEvent;
49  exampleEvent.eventHeader.name = "report";
50  exampleEvent.counter = _heartbeatCounter;
51  _exampleEventSource.publish(exampleEvent);
52 
53  // Reset tick counter
54  tick = 0;
55 
56  // Create distributions
57  std::uniform_int_distribution<uint64_t> intDistribution;
58  std::uniform_real_distribution<double> doubleDistribution;
59 
60  // Publish complex message filled with random values
61  ExampleComplexMessage complexMessage;
62  complexMessage.field1 = intDistribution(_random);
63  complexMessage.field2 = intDistribution(_random);
64  complexMessage.field3 = doubleDistribution(_random);
65  complexMessage.submessage1.field1 = "random1";
66  complexMessage.submessage1.field2 = doubleDistribution(_random);
67  complexMessage.submessage2.field1 = "random2";
68  complexMessage.submessage2.field2 = doubleDistribution(_random);
70  }
71 
72  // Sleep
73  std::this_thread::sleep_for(std::chrono::milliseconds(100));
74  }
75 }
76 
77 void Node::HandleSimpleEvent(const swarmros::SimpleEvent& event)
78 {
79  if (event.eventHeader.name == "ping")
80  {
81  // Respond
82  SimpleEvent pongEvent;
83  pongEvent.eventHeader.name = "pong";
84  pongEvent.eventHeader.node = event.eventHeader.node;
85  _pongEventSource.publish(pongEvent);
86 
87  // Log
88  std::cout << "A response was sent for a ping SimpleEvent to node " << pongEvent.eventHeader.node << std::endl;
89  }
90  else if (event.eventHeader.name == "heartbeat")
91  {
92  // Increment
93  uint64_t current = ++_heartbeatCounter;
94 
95  // Publish update
96  UInt value;
97  value.value = current;
99  }
100  else
101  {
102  std::cout << "Unknown SimpleEvent received: " << event.eventHeader.name << std::endl;
103  }
104 }
105 
106 void Node::HandleExampleEvent(const swarmros::ExampleEvent& event)
107 {
108  if (event.eventHeader.name == "report")
109  {
110  std::cout << "Node " << event.eventHeader.node << " reports that its counter is at " << event.counter << std::endl;
111  }
112  else
113  {
114  std::cout << "Unknown ExampleEvent received: " << event.eventHeader.name << std::endl;
115  }
116 }
117 
118 void Node::HandleIntervalParameterChange(const UInt& value)
119 {
120  // Set interval
121  _reportInterval = value.value;
122 }
123 
125 {
126  _shutdownRequested = true;
127 }
ros::Subscriber _reportIntervalParameterSubscriber
Parameter subscription for report interval.
Node(const std::string &name)
Construct a new Node objet.
Definition: example/Node.cpp:9
std::atomic< bool > _shutdownRequested
Shutdown signal for worker thread.
void HandleIntervalParameterChange(const UInt &value)
Handle parameter changes.
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::atomic< uint64_t > _reportInterval
Report interval.
void HandleSimpleEvent(const SimpleEvent &event)
Handle an incoming SimpleEvent.
std::random_device _random
Random number generator.
~Node()
Destroy the Node object.
ros::Publisher _exampleEventSource
Event source for example events.
ros::Publisher _heartbeatCounterTelemetryPublisher
Telemetry publisher for the heartbeat counter.
ros::Publisher _complexMessageTelemetryPublisher
Telemetry publisher for the complex message.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void HandleExampleEvent(const ExampleEvent &event)
Handle an incoming ExampleEvent.
ros::Publisher _pongEventSource
Event source for pong events.
void Worker()
Entry point for worker thread.
ros::Subscriber _pingEventSink
Event sink for ping events.
std::atomic< uint64_t > _heartbeatCounter
Global heartbeat counter.
ros::Publisher _heartbeatEventSource
Event source for simple events.
ros::Subscriber _exampleEventSink
Event sink for example events.
ros::Subscriber _heartbeatEventSink
Event sink for heartbeat events.
ros::NodeHandle _handle
ROS node handle.


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