heartbeat.h
Go to the documentation of this file.
1 #pragma once
2 
3 // SPDX-License-Identifier: BSD-3-Clause
4 // SPDX-FileCopyrightText: Czech Technical University in Prague
5 
13 #include <memory>
14 
15 #include <ros/message_event.h>
16 #include <ros/publisher.h>
17 #include <ros/subscriber.h>
18 #include <topic_tools/shape_shifter.h>
19 
22 #include <cras_msgs/Heartbeat.h>
23 
25 
26 namespace cras
27 {
28 
57 {
58 protected:
62 
63  void onInit() override;
64 
69  virtual void processMessage(const ::ros::MessageEvent<const ::topic_tools::ShapeShifter>& event);
70 
73 
75  std::unique_ptr<SubscriberType> sub;
76 
78  cras::optional<bool> hasHeader {cras::nullopt};
79 };
80 
81 }
void onInit() override
Definition: heartbeat.cpp:30
Nodelet that republishes heartbeat of a topic with header.
Definition: heartbeat.h:56
virtual void processMessage(const ::ros::MessageEvent< const ::topic_tools::ShapeShifter > &event)
Process the received message.
Definition: heartbeat.cpp:64
std::unique_ptr< SubscriberType > sub
The lazy subscriber.
Definition: heartbeat.h:75
ros::Publisher pub
The publisher of heartbeat messages.
Definition: heartbeat.h:72
Lazy subscriber that subscribes only when a paired publisher has subscribers.
Lazy subscriber that subscribes only when a paired publisher has subscribers.
cras::optional< bool > hasHeader
Whether the subscribed topic has a header field. This is filled on receipt of the first message...
Definition: heartbeat.h:78
LazySubscriber< cras_msgs::Heartbeat, const ros::MessageEvent< const topic_tools::ShapeShifter > & > SubscriberType
The lazy subscriber type.
Definition: heartbeat.h:61


cras_topic_tools
Author(s): Martin Pecka
autogenerated on Sat Jun 17 2023 02:33:13