Template Class TimeSequencer
Defined in File time_sequencer.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public message_filters::SimpleFilter< M >
(Template Class SimpleFilter)
Class Documentation
-
template<class M>
class TimeSequencer : public message_filters::SimpleFilter<M> Sequences messages based on the timestamp of their header.
The TimeSequencer object is templated on the type of message being sequenced.
BEHAVIOR
At construction, the TimeSequencer takes a rclcpp::Duration “delay” which specifies how long to queue up messages to provide a time sequencing over them. As messages arrive they are sorted according to their time stamps. A callback for a message is never invoked until the messages’ time stamp is out of date by at least delay. However, for all messages which are out of date by at least delay, their callback are invoked and guaranteed to be in temporal order. If a message arrives from a time prior to a message which has already had its callback invoked, it is thrown away.
CONNECTIONS
TimeSequencer’s input and output connections are both of the same signature as rclcpp subscription callbacks, ie.
void callback(const std::shared_ptr<M const>&);
Public Functions
Constructor.
- Parameters:
f – A filter to connect this sequencer’s input to
delay – The minimum time to hold a message before passing it through.
update_rate – The rate at which to check for messages which have passed “delay”
queue_size – The number of messages to store
node – The Node to use to create the rclcpp::SteadyTimer that runs at update_rate
Constructor.
This version of the constructor does not take a filter immediately. You can connect to a filter later with the connectInput() function
- Parameters:
delay – The minimum time to hold a message before passing it through.
update_rate – The rate at which to check for messages which have passed “delay”
queue_size – The number of messages to store
node – The Node to use to create the rclcpp::SteadyTimer that runs at update_rate
-
template<class F>
inline void connectInput(F &f) Connect this filter’s input to another filter’s output.
-
inline ~TimeSequencer()