count_messages.h
Go to the documentation of this file.
1 #pragma once
2 
3 // SPDX-License-Identifier: BSD-3-Clause
4 // SPDX-FileCopyrightText: Czech Technical University in Prague
5 
12 #include <mutex>
13 
14 #include <ros/message_event.h>
15 #include <ros/subscriber.h>
16 #include <topic_tools/shape_shifter.h>
17 
19 
20 namespace cras
21 {
22 
39 {
40  void onInit() override;
41 
45  virtual void resetCb(const ::ros::MessageEvent<::topic_tools::ShapeShifter const>&);
46 
51  virtual void cb(const ::ros::MessageEvent<::topic_tools::ShapeShifter const>& event);
52 
55 
58 
60  size_t bytes {0};
61 
63  size_t count {0};
64 
66  ::std::mutex mutex;
67 };
68 
69 }
virtual void cb(const ::ros::MessageEvent<::topic_tools::ShapeShifter const > &event)
Callback for counting the messages.
Nodelet for counting messages and their size.
::std::mutex mutex
Mutex protecting count and bytes.
size_t bytes
Byte size of the received messages.
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...
::ros::Subscriber sub
The message subscriber.
size_t count
Number of received messages.
::ros::Subscriber resetSub
The reset message subscriber.


cras_topic_tools
Author(s): Martin Pecka
autogenerated on Sat Jun 17 2023 02:33:13