Go to the documentation of this file.
19 #include <topic_tools/shape_shifter.h>
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);
38 std::string inTopic =
"input";
39 std::string outTopic =
"output";
46 outTopic = (this->
getMyArgv().size() >= 2 ? this->
getMyArgv()[1] : (inTopic +
"_relay"));
52 this->
pubSub = std::make_unique<cras::GenericLazyPubSub>(nh, inTopic, outTopic, inQueueSize, outQueueSize,
56 this->
pubSub->setLazy(
false);
58 CRAS_INFO(
"Created%s relay from %s to %s.",
59 (lazy ?
" lazy" :
""), nh.resolveName(inTopic).c_str(), nh.resolveName(outTopic).c_str());
virtual void processMessage(const ::ros::MessageEvent< const ::topic_tools::ShapeShifter > &event, ::ros::Publisher &pub)
Republish the received message.
::std::unique_ptr<::cras::GenericLazyPubSub > pubSub
The lazy pair of subscriber and publisher.
::cras::BoundParamHelperPtr privateParams(const ::std::string &ns="") const
TransportHints transport_hints
ros::NodeHandle & getMTPrivateNodeHandle() const
bool allow_concurrent_callbacks
const V_string & getMyArgv() const
const boost::shared_ptr< ConstMessage > & getConstMessage() const
void publish(const boost::shared_ptr< M > &message) const
TransportHints & tcpNoDelay(bool nodelay=true)
Nodelet for relaying messages on a different topic.
Lazy subscriber that subscribes only when a paired publisher has subscribers. Version for unknown mes...
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
This is a simple implementation of a relay nodelet.
auto bind_front(F &&f, Args &&... args)
::cras::BoundParamHelperPtr params(const ::ros::NodeHandle &node, const ::std::string &ns="") const
ros::NodeHandle & getMTNodeHandle() const
cras_topic_tools
Author(s): Martin Pecka
autogenerated on Tue Nov 26 2024 03:49:18