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>&);
141 ::std::unique_ptr<::ros::Rate>
rate;
147 ::cras::optional<::ros::Duration>
maxAge {::cras::nullopt};
bool resetOnMsg
Whether to reset the publication timer when a new message arrives.
::topic_tools::ShapeShifter::ConstPtr msg
The last stored message (null if no message has been received yet).
virtual void maybePublish()
Publish the last stored message (if it is eligible).
void everyPeriod(const ::ros::TimerEvent &)
Timer callback. Publish the last stored message if it is eligible.
Nodelet for repeating messages coming at a slower rate (or even just a single message).
bool discardOlderMessages
Whether to discard an incoming message if its stamp is older than the previously accepted message...
::cras::optional<::ros::Time > lastMsgStamp
Time stamp of the last stored message (only filled if inspectStamps() returns true.
::ros::Timer timer
The timer periodically republishing the last stored message.
virtual bool inspectStamps() const
Whether Header should be extracted from the message and its time stamp should undergo inspection...
::cras::optional< size_t > maxRepeats
Maximum number of repetitions of a single message (only limited when set).
Lazy subscriber that subscribes only when a paired publisher has subscribers. Version for unknown mes...
::cras::optional< bool > hasHeader
void reset()
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::mutex msgMutex
Mutex protecting msg, lastMsgStamp and numRepeats.
::std::unique_ptr<::ros::Rate > rate
The desired output rate.
size_t numRepeats
Number of times the last stored message has been repeated.
bool publishOnlyOnTimer
Whether to publish only on timer events, or also when an incoming message is received.
::std::unique_ptr<::cras::GenericLazyPubSub > pubSub
The lazy pair of subscriber and publisher.
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...
::ros::Subscriber resetSub
Subscriber to the reset topic.
::cras::optional<::ros::Duration > maxAge
Maximum age of a message to allow publishing it (the message has to have a Header).
::ros::Publisher pub
The publisher of the repeated messages.