2 #include <swarmros/ExampleComplexMessage.h> 10 : _handle(name), _shutdownRequested(false), _reportInterval(50), _heartbeatCounter(0)
40 SimpleEvent heartbeatEvent;
41 heartbeatEvent.eventHeader.name =
"heartbeat";
48 ExampleEvent exampleEvent;
49 exampleEvent.eventHeader.name =
"report";
57 std::uniform_int_distribution<uint64_t> intDistribution;
58 std::uniform_real_distribution<double> doubleDistribution;
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);
73 std::this_thread::sleep_for(std::chrono::milliseconds(100));
79 if (event.eventHeader.name ==
"ping")
82 SimpleEvent pongEvent;
83 pongEvent.eventHeader.name =
"pong";
84 pongEvent.eventHeader.node =
event.eventHeader.node;
88 std::cout <<
"A response was sent for a ping SimpleEvent to node " << pongEvent.eventHeader.node << std::endl;
90 else if (event.eventHeader.name ==
"heartbeat")
97 value.value = current;
102 std::cout <<
"Unknown SimpleEvent received: " <<
event.eventHeader.name << std::endl;
108 if (event.eventHeader.name ==
"report")
110 std::cout <<
"Node " <<
event.eventHeader.node <<
" reports that its counter is at " <<
event.counter << std::endl;
114 std::cout <<
"Unknown ExampleEvent received: " <<
event.eventHeader.name << std::endl;
ros::Subscriber _reportIntervalParameterSubscriber
Parameter subscription for report interval.
Node(const std::string &name)
Construct a new Node objet.
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.
std::thread _worker
Worker thread.
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.