Go to the documentation of this file.
12 #include <boost/bind.hpp>
13 #include <boost/bind/placeholders.hpp>
19 #include <topic_tools/shape_shifter.h>
28 std::lock_guard<std::mutex> lock(this->
mutex);
30 this->
bytes +=
event.getConstMessage()->size();
38 const auto inQueueSize = pnh.param(
"in_queue_size", 1000);
39 const auto tcpNoDelay = pnh.param(
"tcp_no_delay",
false);
49 ops.template initByFullCallbackType<const ros::MessageEvent<topic_tools::ShapeShifter const>&>(
51 this->
sub = pnh.subscribe(ops);
55 ops.template initByFullCallbackType<const ros::MessageEvent<topic_tools::ShapeShifter const>&>(
62 std::lock_guard<std::mutex> lock(this->
mutex);
void setParam(const std::string &key, bool b) const
::ros::Subscriber sub
The message subscriber.
TransportHints transport_hints
virtual void resetCb(const ::ros::MessageEvent<::topic_tools::ShapeShifter const > &)
Called when the counter should be reset. The incoming message can be of any type and should not be ex...
::std::mutex mutex
Mutex protecting count and bytes.
ros::NodeHandle & getMTPrivateNodeHandle() const
bool allow_concurrent_callbacks
TransportHints & tcpNoDelay(bool nodelay=true)
Nodelet for counting messages and their size.
size_t bytes
Byte size of the received messages.
Count messages on a topic.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual void cb(const ::ros::MessageEvent<::topic_tools::ShapeShifter const > &event)
Callback for counting the messages.
::ros::Subscriber resetSub
The reset message subscriber.
size_t count
Number of received messages.
cras_topic_tools
Author(s): Martin Pecka
autogenerated on Wed Jan 8 2025 03:50:28