repeat.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 <memory>
13 #include <mutex>
14 #include <string>
15 
16 #include <ros/duration.h>
17 #include <ros/forwards.h>
18 #include <ros/message_event.h>
19 #include <ros/publisher.h>
20 #include <ros/node_handle.h>
21 #include <ros/rate.h>
22 #include <ros/subscriber.h>
23 #include <ros/time.h>
24 #include <ros/timer.h>
25 #include <topic_tools/shape_shifter.h>
26 
29 
31 
32 namespace cras
33 {
34 
95 {
96 protected:
98  ::std::unique_ptr<::cras::GenericLazyPubSub> pubSub;
99 
102 
103  void onInit() override;
104 
109  virtual void onReset(const ::ros::MessageEvent<const ::topic_tools::ShapeShifter>&);
110 
114  void reset();
115 
122  void processMessage(const ::ros::MessageEvent<const ::topic_tools::ShapeShifter>& event, ::ros::Publisher& pub);
123 
127  virtual void maybePublish();
128 
133  virtual bool inspectStamps() const;
134 
138  void everyPeriod(const ::ros::TimerEvent&);
139 
141  ::std::unique_ptr<::ros::Rate> rate;
142 
144  ::cras::optional<size_t> maxRepeats {::cras::nullopt};
145 
147  ::cras::optional<::ros::Duration> maxAge {::cras::nullopt};
148 
150  bool discardOlderMessages {false};
151 
153  bool resetOnMsg {true};
154 
156  bool publishOnlyOnTimer {false};
157 
159  ::std::mutex msgMutex;
160 
163 
165  ::cras::optional<::ros::Time> lastMsgStamp;
166 
168  size_t numRepeats {0};
169 
170  ::cras::optional<bool> hasHeader {::cras::nullopt};
171 
174 
177 };
178 
179 }
optional.hpp
cras::RepeatMessagesNodelet::resetSub
::ros::Subscriber resetSub
Subscriber to the reset topic.
Definition: repeat.h:101
forwards.h
node_handle.h
ros::Publisher
cras::RepeatMessagesNodelet::onInit
void onInit() override
Definition: repeat.cpp:38
boost::shared_ptr< ShapeShifter const >
cras
cras::RepeatMessagesNodelet::everyPeriod
void everyPeriod(const ::ros::TimerEvent &)
Timer callback. Publish the last stored message if it is eligible.
Definition: repeat.cpp:211
cras::RepeatMessagesNodelet::maxAge
::cras::optional<::ros::Duration > maxAge
Maximum age of a message to allow publishing it (the message has to have a Header).
Definition: repeat.h:147
cras::RepeatMessagesNodelet::timer
::ros::Timer timer
The timer periodically republishing the last stored message.
Definition: repeat.h:173
time.h
cras::RepeatMessagesNodelet::rate
::std::unique_ptr<::ros::Rate > rate
The desired output rate.
Definition: repeat.h:141
cras::RepeatMessagesNodelet::inspectStamps
virtual bool inspectStamps() const
Whether Header should be extracted from the message and its time stamp should undergo inspection.
Definition: repeat.cpp:206
cras::RepeatMessagesNodelet::discardOlderMessages
bool discardOlderMessages
Whether to discard an incoming message if its stamp is older than the previously accepted message.
Definition: repeat.h:150
publisher.h
cras::RepeatMessagesNodelet::maybePublish
virtual void maybePublish()
Publish the last stored message (if it is eligible).
Definition: repeat.cpp:181
ros::Timer
generic_lazy_pubsub.hpp
Lazy subscriber that subscribes only when a paired publisher has subscribers. Version for unknown mes...
cras::RepeatMessagesNodelet::publishOnlyOnTimer
bool publishOnlyOnTimer
Whether to publish only on timer events, or also when an incoming message is received.
Definition: repeat.h:156
duration.h
cras::RepeatMessagesNodelet::pub
::ros::Publisher pub
The publisher of the repeated messages.
Definition: repeat.h:176
subscriber.h
rate.h
cras::RepeatMessagesNodelet::onReset
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...
Definition: repeat.cpp:101
cras::RepeatMessagesNodelet::pubSub
::std::unique_ptr<::cras::GenericLazyPubSub > pubSub
The lazy pair of subscriber and publisher.
Definition: repeat.h:98
ros::Publisher
timer.h
cras::RepeatMessagesNodelet::reset
void reset()
Reset the repeater, e.g. after a time jump.
Definition: repeat.cpp:106
cras::RepeatMessagesNodelet::numRepeats
size_t numRepeats
Number of times the last stored message has been repeated.
Definition: repeat.h:168
cras::RepeatMessagesNodelet::processMessage
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.
Definition: repeat.cpp:116
cras::RepeatMessagesNodelet
Nodelet for repeating messages coming at a slower rate (or even just a single message).
Definition: repeat.h:94
cras::Nodelet
cras::RepeatMessagesNodelet::resetOnMsg
bool resetOnMsg
Whether to reset the publication timer when a new message arrives.
Definition: repeat.h:153
cras::RepeatMessagesNodelet::hasHeader
::cras::optional< bool > hasHeader
Definition: repeat.h:170
ros::Subscriber
cras::RepeatMessagesNodelet::lastMsgStamp
::cras::optional<::ros::Time > lastMsgStamp
Time stamp of the last stored message (only filled if inspectStamps() returns true.
Definition: repeat.h:165
message_event.h
cras::RepeatMessagesNodelet::maxRepeats
::cras::optional< size_t > maxRepeats
Maximum number of repetitions of a single message (only limited when set).
Definition: repeat.h:144
cras::RepeatMessagesNodelet::msgMutex
::std::mutex msgMutex
Mutex protecting msg, lastMsgStamp and numRepeats.
Definition: repeat.h:159
nodelet_utils.hpp
cras::RepeatMessagesNodelet::msg
::topic_tools::ShapeShifter::ConstPtr msg
The last stored message (null if no message has been received yet).
Definition: repeat.h:162


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