throttle_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 
14 #include <memory>
15 #include <mutex>
16 
17 #include <ros/message_event.h>
18 #include <ros/publisher.h>
19 #include <ros/subscriber.h>
20 #include <topic_tools/shape_shifter.h>
21 
24 
26 
27 namespace cras
28 {
29 
79 {
80 protected:
82  ::std::unique_ptr<::cras::GenericLazyPubSub> pubSub;
83 
86 
87  void onInit() override;
88 
93  virtual void onReset(const ::ros::MessageEvent<const ::topic_tools::ShapeShifter>&);
94 
98  void reset();
99 
106  void processMessage(const ::ros::MessageEvent<const ::topic_tools::ShapeShifter>& event, ::ros::Publisher& pub);
107 
109  ::std::unique_ptr<::cras::RateLimiter> limiter;
110 
112  ::std::mutex limiterMutex;
113 };
114 
115 }
cras::ThrottleMessagesNodelet
Nodelet for throttling messages on a topic.
Definition: throttle_messages.h:78
rate_limiter.h
ros::Publisher
cras
cras::ThrottleMessagesNodelet::pubSub
::std::unique_ptr<::cras::GenericLazyPubSub > pubSub
The lazy pair of subscriber and publisher.
Definition: throttle_messages.h:82
cras::ThrottleMessagesNodelet::onInit
void onInit() override
Definition: throttle_messages.cpp:37
cras::ThrottleMessagesNodelet::onReset
virtual void onReset(const ::ros::MessageEvent< const ::topic_tools::ShapeShifter > &)
Called when the rate limiter should be reset. The incoming message can be of any type and should not ...
Definition: throttle_messages.cpp:106
publisher.h
generic_lazy_pubsub.hpp
Lazy subscriber that subscribes only when a paired publisher has subscribers. Version for unknown mes...
cras::ThrottleMessagesNodelet::resetSub
::ros::Subscriber resetSub
Subscriber to the reset topic.
Definition: throttle_messages.h:85
cras::ThrottleMessagesNodelet::limiterMutex
::std::mutex limiterMutex
Mutex for working with the limiter.
Definition: throttle_messages.h:112
subscriber.h
cras::ThrottleMessagesNodelet::processMessage
void processMessage(const ::ros::MessageEvent< const ::topic_tools::ShapeShifter > &event, ::ros::Publisher &pub)
Publish the incoming message if the rate limiter allows.
Definition: throttle_messages.cpp:117
cras::ThrottleMessagesNodelet::limiter
::std::unique_ptr<::cras::RateLimiter > limiter
The rate limiter used for limiting output rate.
Definition: throttle_messages.h:109
cras::ThrottleMessagesNodelet::reset
void reset()
Reset the rate limiter, e.g. after a time jump.
Definition: throttle_messages.cpp:111
cras::Nodelet
ros::Subscriber
message_event.h
nodelet_utils.hpp


cras_topic_tools
Author(s): Martin Pecka
autogenerated on Sat Mar 2 2024 03:47:49