Sequences messages based on the timestamp of their header. More...
#include <time_sequencer.h>
Classes | |
class | MessageSort |
Public Types | |
typedef ros::MessageEvent< M const > | EventType |
typedef boost::shared_ptr< M const > | MConstPtr |
Public Member Functions | |
void | add (const EventType &evt) |
void | add (const MConstPtr &msg) |
Manually add a message to the cache. More... | |
template<class F > | |
void | connectInput (F &f) |
Connect this filter's input to another filter's output. More... | |
template<class F > | |
TimeSequencer (F &f, ros::Duration delay, ros::Duration update_rate, uint32_t queue_size, ros::NodeHandle nh=ros::NodeHandle()) | |
Constructor. More... | |
TimeSequencer (ros::Duration delay, ros::Duration update_rate, uint32_t queue_size, ros::NodeHandle nh=ros::NodeHandle()) | |
Constructor. More... | |
~TimeSequencer () | |
Private Types | |
typedef std::multiset< EventType, MessageSort > | S_Message |
typedef std::vector< EventType > | V_Message |
Private Member Functions | |
void | cb (const EventType &evt) |
void | dispatch () |
void | init () |
void | update (const ros::TimerEvent &) |
Private Attributes | |
ros::Duration | delay_ |
Connection | incoming_connection_ |
ros::Time | last_time_ |
S_Message | messages_ |
boost::mutex | messages_mutex_ |
ros::NodeHandle | nh_ |
uint32_t | queue_size_ |
ros::Duration | update_rate_ |
ros::Timer | update_timer_ |
Additional Inherited Members |
Sequences messages based on the timestamp of their header.
The TimeSequencer object is templated on the type of message being sequenced.
At construction, the TimeSequencer takes a ros::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.
TimeSequencer's input and output connections are both of the same signature as roscpp subscription callbacks, ie.
void callback(const boost::shared_ptr<M const>&);
Definition at line 75 of file time_sequencer.h.
typedef ros::MessageEvent<M const> message_filters::TimeSequencer< M >::EventType |
Definition at line 79 of file time_sequencer.h.
typedef boost::shared_ptr<M const> message_filters::TimeSequencer< M >::MConstPtr |
Definition at line 78 of file time_sequencer.h.
|
private |
Definition at line 172 of file time_sequencer.h.
|
private |
Definition at line 173 of file time_sequencer.h.
|
inline |
Constructor.
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 |
nh | (optional) The NodeHandle to use to create the ros::Timer that runs at update_rate |
Definition at line 90 of file time_sequencer.h.
|
inline |
Constructor.
This version of the constructor does not take a filter immediately. You can connect to a filter later with the connectInput() function
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 |
nh | (optional) The NodeHandle to use to create the ros::Timer that runs at update_rate |
Definition at line 110 of file time_sequencer.h.
|
inline |
Definition at line 129 of file time_sequencer.h.
|
inline |
Definition at line 135 of file time_sequencer.h.
|
inline |
Manually add a message to the cache.
Definition at line 156 of file time_sequencer.h.
|
inlineprivate |
Definition at line 175 of file time_sequencer.h.
|
inline |
Connect this filter's input to another filter's output.
Definition at line 123 of file time_sequencer.h.
|
inlineprivate |
Definition at line 180 of file time_sequencer.h.
|
inlineprivate |
Definition at line 221 of file time_sequencer.h.
|
inlineprivate |
Definition at line 216 of file time_sequencer.h.
|
private |
Definition at line 226 of file time_sequencer.h.
|
private |
Definition at line 233 of file time_sequencer.h.
|
private |
Definition at line 238 of file time_sequencer.h.
|
private |
Definition at line 236 of file time_sequencer.h.
|
private |
Definition at line 237 of file time_sequencer.h.
|
private |
Definition at line 229 of file time_sequencer.h.
|
private |
Definition at line 228 of file time_sequencer.h.
|
private |
Definition at line 227 of file time_sequencer.h.
|
private |
Definition at line 231 of file time_sequencer.h.