20 #include <topic_tools/shape_shifter.h> 82 ::std::unique_ptr<::cras::GenericLazyPubSub>
pubSub;
93 virtual void onReset(const ::ros::MessageEvent<const ::topic_tools::ShapeShifter>&);
109 ::std::unique_ptr<::cras::RateLimiter>
limiter;
void reset()
Reset the rate limiter, e.g. after a time jump.
void processMessage(const ::ros::MessageEvent< const ::topic_tools::ShapeShifter > &event, ::ros::Publisher &pub)
Publish the incoming message if the rate limiter allows.
Nodelet for throttling messages on a topic.
::ros::Subscriber resetSub
Subscriber to the reset topic.
::std::unique_ptr<::cras::RateLimiter > limiter
The rate limiter used for limiting output rate.
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 ...
Lazy subscriber that subscribes only when a paired publisher has subscribers. Version for unknown mes...
::std::unique_ptr<::cras::GenericLazyPubSub > pubSub
The lazy pair of subscriber and publisher.
::std::mutex limiterMutex
Mutex for working with the limiter.