count_messages.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 <mutex>
11 
12 #include <boost/bind.hpp>
13 #include <boost/bind/placeholders.hpp>
14 
15 #include <nodelet/nodelet.h>
17 #include <ros/message_event.h>
18 #include <ros/subscribe_options.h>
19 #include <topic_tools/shape_shifter.h>
20 
22 
23 namespace cras
24 {
25 
27 {
28  std::lock_guard<std::mutex> lock(this->mutex);
29  this->count++;
30  this->bytes += event.getConstMessage()->size();
31  this->getMTPrivateNodeHandle().setParam("count", static_cast<int>(this->count));
32  this->getMTPrivateNodeHandle().setParam("bytes", static_cast<int>(this->bytes));
33 }
34 
36 {
37  auto pnh = this->getMTPrivateNodeHandle();
38  const auto inQueueSize = pnh.param("in_queue_size", 1000);
39  const auto tcpNoDelay = pnh.param("tcp_no_delay", false);
40 
41  this->getMTPrivateNodeHandle().setParam("bytes", 0);
42  this->getMTPrivateNodeHandle().setParam("count", 0);
43 
44  // we cannot use the simple one-liner pnh.subscribe() - otherwise there's double free from
45  // https://github.com/ros/ros_comm/pull/1722
47  ops.allow_concurrent_callbacks = true;
48  ops.transport_hints.tcpNoDelay(tcpNoDelay);
49  ops.template initByFullCallbackType<const ros::MessageEvent<topic_tools::ShapeShifter const>&>(
50  "input", inQueueSize, boost::bind(&CountMessagesNodelet::cb, this, boost::placeholders::_1));
51  this->sub = pnh.subscribe(ops);
52 
53  ops.allow_concurrent_callbacks = false;
54  ops.transport_hints.tcpNoDelay(true);
55  ops.template initByFullCallbackType<const ros::MessageEvent<topic_tools::ShapeShifter const>&>(
56  "reset", inQueueSize, boost::bind(&CountMessagesNodelet::resetCb, this, boost::placeholders::_1));
57  this->resetSub = pnh.subscribe(ops);
58 }
59 
61 {
62  std::lock_guard<std::mutex> lock(this->mutex);
63  this->count = this->bytes = 0;
64  this->getMTPrivateNodeHandle().setParam("count", 0);
65  this->getMTPrivateNodeHandle().setParam("bytes", 0);
66 }
67 
68 }
69 
ros::NodeHandle::setParam
void setParam(const std::string &key, bool b) const
cras::CountMessagesNodelet::sub
::ros::Subscriber sub
The message subscriber.
Definition: count_messages.h:54
cras
ros::SubscribeOptions::transport_hints
TransportHints transport_hints
cras::CountMessagesNodelet::resetCb
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...
Definition: count_messages.cpp:60
cras::CountMessagesNodelet::mutex
::std::mutex mutex
Mutex protecting count and bytes.
Definition: count_messages.h:66
nodelet::Nodelet::getMTPrivateNodeHandle
ros::NodeHandle & getMTPrivateNodeHandle() const
ros::SubscribeOptions::allow_concurrent_callbacks
bool allow_concurrent_callbacks
ros::TransportHints::tcpNoDelay
TransportHints & tcpNoDelay(bool nodelay=true)
cras::CountMessagesNodelet
Nodelet for counting messages and their size.
Definition: count_messages.h:38
cras::CountMessagesNodelet::bytes
size_t bytes
Byte size of the received messages.
Definition: count_messages.h:60
count_messages.h
Count messages on a topic.
class_list_macros.h
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
cras::CountMessagesNodelet::onInit
void onInit() override
Definition: count_messages.cpp:35
cras::CountMessagesNodelet::cb
virtual void cb(const ::ros::MessageEvent<::topic_tools::ShapeShifter const > &event)
Callback for counting the messages.
Definition: count_messages.cpp:26
cras::CountMessagesNodelet::resetSub
::ros::Subscriber resetSub
The reset message subscriber.
Definition: count_messages.h:57
cras::CountMessagesNodelet::count
size_t count
Number of received messages.
Definition: count_messages.h:63
nodelet::Nodelet
ros::SubscribeOptions
nodelet.h
message_event.h
subscribe_options.h
ros::MessageEvent


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