Class HeartbeatNodelet
Defined in File heartbeat.h
Inheritance Relationships
Base Type
public cras::Nodelet
Class Documentation
-
class HeartbeatNodelet : public cras::Nodelet
Nodelet that republishes heartbeat of a topic with header.
ROS parameters:
~queue_size(uint, default 10): Queue size for the subscriber and publisher.~lazy(bool, default False): Whether to shut down the subscriber when the publisher has no subscribers.~tcp_no_delay(bool, default False): If True, theTCP_NODELAYflag is set for the subscriber. This should decrease the latency of small messages, but might give suboptimal transmission speed for large messages.
Subscribed topics:
~input(any type with header): The input messages. Iflazyis true, it will only be subscribed when~input/heartbeathas some subscribers. If you subscribe to a message type without header, the node should not crash, but it will discard all received messages and print an error message.
Published topics:
~input/heartbeat(cras_msgs/Heartbeat): The heartbeat.
Command-line arguments: This nodelet (or node) can also be called in a way backwards compatible with topic_tools nodes. This means you can pass CLI arguments specifying the topic to subscribe.
rosrun cras_topic_tools heartbeat [TOPIC_IN]TOPIC_IN: The topic to subscribe. It is resolved against parent namespace of the node(let) (as opposed to the~inputtopic which is resolved against the private node(let) namespace). The heartbeat topic will beTOPIC_IN/heartbeat.
Protected Types
-
typedef LazySubscriber<cras_msgs::Heartbeat, const ros::MessageEvent<const topic_tools::ShapeShifter>&> SubscriberType
The lazy subscriber type.
Protected Functions
-
void onInit() override
-
virtual void processMessage(const ::ros::MessageEvent<const ::topic_tools::ShapeShifter> &event)
Process the received message.
- Parameters:
event – [in] The message event containing the received message.
Protected Attributes
-
ros::Publisher pub
The publisher of heartbeat messages.
-
std::unique_ptr<SubscriberType> sub
The lazy subscriber.
-
cras::optional<bool> hasHeader = {cras::nullopt}
Whether the subscribed topic has a header field. This is filled on receipt of the first message.