Go to the documentation of this file.
18 #include <topic_tools/shape_shifter.h>
21 #include <cras_msgs/Heartbeat.h>
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);
38 std::string topic =
"input";
49 this->
pub = nh.advertise<cras_msgs::Heartbeat>(heartbeatTopic, queueSize);
53 opts.transport_hints.tcpNoDelay(tcpNoDelay);
54 this->
sub = std::make_unique<SubscriberType>(nh, heartbeatTopic, nh, topic, queueSize,
58 this->
sub->setLazy(
false);
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());
66 const auto&
msg =
event.getConstMessage();
74 CRAS_ERROR(
"Heartbeat did not find a header in message type %s! Ignoring all messages.",
85 CRAS_ERROR(
"Heartbeat failed to extract a header from the message of type %s! Ignoring the message.",
90 cras_msgs::Heartbeat heartbeat;
91 heartbeat.header = *
header;
92 this->
pub.template publish(heartbeat);
bool hasHeader(const ::topic_tools::ShapeShifter &msg)
Tell whether the given message has header field.
Tools for more convenient working with ShapeShifter objects.
::cras::BoundParamHelperPtr privateParams(const ::std::string &ns="") const
cras::optional< bool > hasHeader
Whether the subscribed topic has a header field. This is filled on receipt of the first message.
ros::NodeHandle & getMTPrivateNodeHandle() const
bool allow_concurrent_callbacks
virtual void processMessage(const ::ros::MessageEvent< const ::topic_tools::ShapeShifter > &event)
Process the received message.
Lazy subscriber that subscribes only when a paired publisher has subscribers.
const V_string & getMyArgv() const
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
std::unique_ptr< SubscriberType > sub
The lazy subscriber.
Nodelet that republishes heartbeat of a topic with header.
This is a nodelet that republishes heartbeat of a topic with header.
ros::Publisher pub
The publisher of heartbeat messages.
auto bind_front(F &&f, Args &&... args)
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
::cras::BoundParamHelperPtr params(const ::ros::NodeHandle &node, const ::std::string &ns="") const
M_string & getConnectionHeader() const
::cras::optional<::std_msgs::Header > getHeader(const ::topic_tools::ShapeShifter &msg)
Get the header field of the given message, if it has any.
ros::NodeHandle & getMTNodeHandle() const
cras_topic_tools
Author(s): Martin Pecka
autogenerated on Wed Jan 8 2025 03:50:28