heartbeat.cpp
Go to the documentation of this file.
1 // SPDX-License-Identifier: BSD-3-Clause
2 // SPDX-FileCopyrightText: Czech Technical University in Prague
3 
10 #include <memory>
11 #include <string>
12 
13 #include <nodelet/nodelet.h>
15 #include <ros/message_event.h>
16 #include <ros/names.h>
17 #include <ros/subscribe_options.h>
18 #include <topic_tools/shape_shifter.h>
19 
21 #include <cras_msgs/Heartbeat.h>
22 
26 
27 namespace cras
28 {
29 
31 {
32  const auto params = this->privateParams();
33  const auto queueSize = params->getParam("queue_size", 10);
34  const auto lazy = params->getParam("lazy", false);
35  const auto tcpNoDelay = params->getParam("tcp_no_delay", false);
36 
37  auto nh = this->getMTPrivateNodeHandle();
38  std::string topic = "input";
39 
40  // Mimic the behavior of topic_tools nodes when called with CLI args
41  if (!this->getMyArgv().empty())
42  {
43  nh = this->getMTNodeHandle();
44  topic = this->getMyArgv()[0];
45  }
46 
47  const auto heartbeatTopic = ros::names::append(nh.resolveName(topic), "heartbeat");
48 
49  this->pub = nh.advertise<cras_msgs::Heartbeat>(heartbeatTopic, queueSize);
50 
52  opts.allow_concurrent_callbacks = true;
53  opts.transport_hints.tcpNoDelay(tcpNoDelay);
54  this->sub = std::make_unique<SubscriberType>(nh, heartbeatTopic, nh, topic, queueSize,
56 
57  if (!lazy)
58  this->sub->setLazy(false);
59 
60  CRAS_INFO("Created%s heartbeat subscribing to %s and publishing to %s.",
61  (lazy ? " lazy" : ""), nh.resolveName(topic).c_str(), nh.resolveName(heartbeatTopic).c_str());
62 }
63 
65 {
66  const auto& msg = event.getConstMessage();
67 
68  if (!this->hasHeader.has_value())
69  {
70  this->hasHeader = cras::hasHeader(*msg);
71 
72  if (!this->hasHeader.value())
73  {
74  CRAS_ERROR("Heartbeat did not find a header in message type %s! Ignoring all messages.",
75  event.getConnectionHeader()["type"].c_str());
76  }
77  }
78 
79  if (!this->hasHeader.value())
80  return;
81 
82  auto header = cras::getHeader(*msg);
83  if (!header.has_value())
84  {
85  CRAS_ERROR("Heartbeat failed to extract a header from the message of type %s! Ignoring the message.",
86  event.getConnectionHeader()["type"].c_str());
87  return;
88  }
89 
90  cras_msgs::Heartbeat heartbeat;
91  heartbeat.header = *header;
92  this->pub.template publish(heartbeat);
93 }
94 
95 }
96 
msg
msg
cras
cras::hasHeader
bool hasHeader(const ::topic_tools::ShapeShifter &msg)
Tell whether the given message has header field.
cras::HeartbeatNodelet::onInit
void onInit() override
Definition: heartbeat.cpp:30
shape_shifter.h
Tools for more convenient working with ShapeShifter objects.
NodeletParamHelper< ::nodelet::Nodelet >::privateParams
::cras::BoundParamHelperPtr privateParams(const ::std::string &ns="") const
cras::HeartbeatNodelet::hasHeader
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
nodelet::Nodelet::getMTPrivateNodeHandle
ros::NodeHandle & getMTPrivateNodeHandle() const
ros::SubscribeOptions::allow_concurrent_callbacks
bool allow_concurrent_callbacks
cras::HeartbeatNodelet::processMessage
virtual void processMessage(const ::ros::MessageEvent< const ::topic_tools::ShapeShifter > &event)
Process the received message.
Definition: heartbeat.cpp:64
lazy_subscriber.hpp
Lazy subscriber that subscribes only when a paired publisher has subscribers.
nodelet::Nodelet::getMyArgv
const V_string & getMyArgv() const
CRAS_ERROR
#define CRAS_ERROR(...)
functional.hpp
CRAS_INFO
#define CRAS_INFO(...)
class_list_macros.h
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
cras::HeartbeatNodelet::sub
std::unique_ptr< SubscriberType > sub
The lazy subscriber.
Definition: heartbeat.h:75
cras::HeartbeatNodelet
Nodelet that republishes heartbeat of a topic with header.
Definition: heartbeat.h:56
heartbeat.h
This is a nodelet that republishes heartbeat of a topic with header.
cras::HeartbeatNodelet::pub
ros::Publisher pub
The publisher of heartbeat messages.
Definition: heartbeat.h:72
cras::bind_front
auto bind_front(F &&f, Args &&... args)
nodelet::Nodelet
ros::names::append
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
ros::SubscribeOptions
names.h
NodeletParamHelper< ::nodelet::Nodelet >::params
::cras::BoundParamHelperPtr params(const ::ros::NodeHandle &node, const ::std::string &ns="") const
nodelet.h
cras::HasLogger::log
::cras::LogHelperPtr log
ros::MessageEvent::getConnectionHeader
M_string & getConnectionHeader() const
header
const std::string header
message_event.h
subscribe_options.h
cras::getHeader
::cras::optional<::std_msgs::Header > getHeader(const ::topic_tools::ShapeShifter &msg)
Get the header field of the given message, if it has any.
ros::MessageEvent
nodelet::Nodelet::getMTNodeHandle
ros::NodeHandle & getMTNodeHandle() const


cras_topic_tools
Author(s): Martin Pecka
autogenerated on Mon Jun 17 2024 02:49:11