relay.cpp
Go to the documentation of this file.
1 // SPDX-License-Identifier: BSD-3-Clause
2 // SPDX-FileCopyrightText: Czech Technical University in Prague
3 
11 #include <memory>
12 #include <string>
13 
14 #include <nodelet/nodelet.h>
16 #include <ros/message_event.h>
17 #include <ros/publisher.h>
18 #include <ros/subscribe_options.h>
19 #include <topic_tools/shape_shifter.h>
20 
22 
24 #include <cras_topic_tools/relay.h>
25 
26 namespace cras
27 {
28 
30 {
31  const auto params = this->privateParams();
32  const auto inQueueSize = params->getParam("in_queue_size", 10);
33  const auto outQueueSize = params->getParam("out_queue_size", inQueueSize);
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 inTopic = "input";
39  std::string outTopic = "output";
40 
41  // Mimic the behavior of topic_tools/relay when called with CLI args
42  if (!this->getMyArgv().empty())
43  {
44  nh = this->getMTNodeHandle();
45  inTopic = this->getMyArgv()[0];
46  outTopic = (this->getMyArgv().size() >= 2 ? this->getMyArgv()[1] : (inTopic + "_relay"));
47  }
48 
50  opts.allow_concurrent_callbacks = true;
51  opts.transport_hints.tcpNoDelay(tcpNoDelay);
52  this->pubSub = std::make_unique<cras::GenericLazyPubSub>(nh, inTopic, outTopic, inQueueSize, outQueueSize,
54 
55  if (!lazy)
56  this->pubSub->setLazy(false);
57 
58  CRAS_INFO("Created%s relay from %s to %s.",
59  (lazy ? " lazy" : ""), nh.resolveName(inTopic).c_str(), nh.resolveName(outTopic).c_str());
60 }
61 
64 {
65  pub.publish(event.getConstMessage());
66 }
67 
68 }
69 
cras::RelayNodelet::processMessage
virtual void processMessage(const ::ros::MessageEvent< const ::topic_tools::ShapeShifter > &event, ::ros::Publisher &pub)
Republish the received message.
Definition: relay.cpp:62
ros::Publisher
cras::RelayNodelet::pubSub
::std::unique_ptr<::cras::GenericLazyPubSub > pubSub
The lazy pair of subscriber and publisher.
Definition: relay.h:61
cras
NodeletParamHelper< ::nodelet::Nodelet >::privateParams
::cras::BoundParamHelperPtr privateParams(const ::std::string &ns="") const
ros::SubscribeOptions::transport_hints
TransportHints transport_hints
nodelet::Nodelet::getMTPrivateNodeHandle
ros::NodeHandle & getMTPrivateNodeHandle() const
ros::SubscribeOptions::allow_concurrent_callbacks
bool allow_concurrent_callbacks
nodelet::Nodelet::getMyArgv
const V_string & getMyArgv() const
ros::MessageEvent::getConstMessage
const boost::shared_ptr< ConstMessage > & getConstMessage() const
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
publisher.h
ros::TransportHints::tcpNoDelay
TransportHints & tcpNoDelay(bool nodelay=true)
cras::RelayNodelet
Nodelet for relaying messages on a different topic.
Definition: relay.h:57
functional.hpp
CRAS_INFO
#define CRAS_INFO(...)
cras::RelayNodelet::onInit
void onInit() override
Definition: relay.cpp:29
class_list_macros.h
generic_lazy_pubsub.hpp
Lazy subscriber that subscribes only when a paired publisher has subscribers. Version for unknown mes...
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
relay.h
This is a simple implementation of a relay nodelet.
cras::bind_front
auto bind_front(F &&f, Args &&... args)
nodelet::Nodelet
ros::SubscribeOptions
NodeletParamHelper< ::nodelet::Nodelet >::params
::cras::BoundParamHelperPtr params(const ::ros::NodeHandle &node, const ::std::string &ns="") const
nodelet.h
cras::HasLogger::log
::cras::LogHelperPtr log
message_event.h
subscribe_options.h
ros::MessageEvent
nodelet::Nodelet::getMTNodeHandle
ros::NodeHandle & getMTNodeHandle() const


cras_topic_tools
Author(s): Martin Pecka
autogenerated on Tue Nov 26 2024 03:49:18