Go to the documentation of this file.
25 #include <topic_tools/shape_shifter.h>
98 ::std::unique_ptr<::cras::GenericLazyPubSub>
pubSub;
109 virtual void onReset(const ::ros::MessageEvent<const ::topic_tools::ShapeShifter>&);
114 void reset()
override;
141 ::std::unique_ptr<::ros::Rate>
rate;
147 ::cras::optional<::ros::Duration>
maxAge {::cras::nullopt};
::ros::Subscriber resetSub
Subscriber to the reset topic.
void everyPeriod(const ::ros::TimerEvent &)
Timer callback. Publish the last stored message if it is eligible.
::cras::optional<::ros::Duration > maxAge
Maximum age of a message to allow publishing it (the message has to have a Header).
::ros::Timer timer
The timer periodically republishing the last stored message.
::std::unique_ptr<::ros::Rate > rate
The desired output rate.
virtual bool inspectStamps() const
Whether Header should be extracted from the message and its time stamp should undergo inspection.
bool discardOlderMessages
Whether to discard an incoming message if its stamp is older than the previously accepted message.
virtual void maybePublish()
Publish the last stored message (if it is eligible).
Lazy subscriber that subscribes only when a paired publisher has subscribers. Version for unknown mes...
bool publishOnlyOnTimer
Whether to publish only on timer events, or also when an incoming message is received.
::ros::Publisher pub
The publisher of the repeated messages.
void reset() override
Reset the repeater, e.g. after a time jump.
virtual void onReset(const ::ros::MessageEvent< const ::topic_tools::ShapeShifter > &)
Called when the repeater should be reset. The incoming message can be of any type and should not be e...
::std::unique_ptr<::cras::GenericLazyPubSub > pubSub
The lazy pair of subscriber and publisher.
size_t numRepeats
Number of times the last stored message has been repeated.
void processMessage(const ::ros::MessageEvent< const ::topic_tools::ShapeShifter > &event, ::ros::Publisher &pub)
Record the incoming message if it passes validations, and publish it if publishOnlyOnTimer is false.
Nodelet for repeating messages coming at a slower rate (or even just a single message).
bool resetOnMsg
Whether to reset the publication timer when a new message arrives.
::cras::optional< bool > hasHeader
::cras::optional<::ros::Time > lastMsgStamp
Time stamp of the last stored message (only filled if inspectStamps() returns true.
::cras::optional< size_t > maxRepeats
Maximum number of repetitions of a single message (only limited when set).
::std::mutex msgMutex
Mutex protecting msg, lastMsgStamp and numRepeats.
::topic_tools::ShapeShifter::ConstPtr msg
The last stored message (null if no message has been received yet).
cras_topic_tools
Author(s): Martin Pecka
autogenerated on Tue Nov 26 2024 03:49:18