Classes | Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes
message_filters::TimeSequencer< M > Class Template Reference

Sequences messages based on the timestamp of their header. More...

#include <time_sequencer.h>

Inheritance diagram for message_filters::TimeSequencer< M >:
Inheritance graph
[legend]

List of all members.

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.
template<class F >
void connectInput (F &f)
 Connect this filter's input to another filter's output.
template<class F >
 TimeSequencer (F &f, ros::Duration delay, ros::Duration update_rate, uint32_t queue_size, ros::NodeHandle nh=ros::NodeHandle())
 Constructor.
 TimeSequencer (ros::Duration delay, ros::Duration update_rate, uint32_t queue_size, ros::NodeHandle nh=ros::NodeHandle())
 Constructor.
 ~TimeSequencer ()

Private Types

typedef std::multiset
< EventType, MessageSort
S_Message
typedef std::vector< EventTypeV_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_

Detailed Description

template<class M>
class message_filters::TimeSequencer< 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 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.

CONNECTIONS

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.


Member Typedef Documentation

template<class M>
typedef ros::MessageEvent<M const> message_filters::TimeSequencer< M >::EventType

Reimplemented from message_filters::SimpleFilter< M >.

Definition at line 79 of file time_sequencer.h.

template<class M>
typedef boost::shared_ptr<M const> message_filters::TimeSequencer< M >::MConstPtr

Reimplemented from message_filters::SimpleFilter< M >.

Definition at line 78 of file time_sequencer.h.

template<class M>
typedef std::multiset<EventType, MessageSort> message_filters::TimeSequencer< M >::S_Message [private]

Definition at line 172 of file time_sequencer.h.

template<class M>
typedef std::vector<EventType> message_filters::TimeSequencer< M >::V_Message [private]

Definition at line 173 of file time_sequencer.h.


Constructor & Destructor Documentation

template<class M>
template<class F >
message_filters::TimeSequencer< M >::TimeSequencer ( F &  f,
ros::Duration  delay,
ros::Duration  update_rate,
uint32_t  queue_size,
ros::NodeHandle  nh = ros::NodeHandle() 
) [inline]

Constructor.

Parameters:
fA filter to connect this sequencer's input to
delayThe minimum time to hold a message before passing it through.
update_rateThe rate at which to check for messages which have passed "delay"
queue_sizeThe 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.

template<class M>
message_filters::TimeSequencer< M >::TimeSequencer ( ros::Duration  delay,
ros::Duration  update_rate,
uint32_t  queue_size,
ros::NodeHandle  nh = ros::NodeHandle() 
) [inline]

Constructor.

This version of the constructor does not take a filter immediately. You can connect to a filter later with the connectInput() function

Parameters:
delayThe minimum time to hold a message before passing it through.
update_rateThe rate at which to check for messages which have passed "delay"
queue_sizeThe 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.

template<class M>
message_filters::TimeSequencer< M >::~TimeSequencer ( ) [inline]

Definition at line 129 of file time_sequencer.h.


Member Function Documentation

template<class M>
void message_filters::TimeSequencer< M >::add ( const EventType evt) [inline]

Definition at line 135 of file time_sequencer.h.

template<class M>
void message_filters::TimeSequencer< M >::add ( const MConstPtr msg) [inline]

Manually add a message to the cache.

Definition at line 156 of file time_sequencer.h.

template<class M>
void message_filters::TimeSequencer< M >::cb ( const EventType evt) [inline, private]

Definition at line 175 of file time_sequencer.h.

template<class M>
template<class F >
void message_filters::TimeSequencer< M >::connectInput ( F &  f) [inline]

Connect this filter's input to another filter's output.

Definition at line 123 of file time_sequencer.h.

template<class M>
void message_filters::TimeSequencer< M >::dispatch ( ) [inline, private]

Definition at line 180 of file time_sequencer.h.

template<class M>
void message_filters::TimeSequencer< M >::init ( ) [inline, private]

Definition at line 221 of file time_sequencer.h.

template<class M>
void message_filters::TimeSequencer< M >::update ( const ros::TimerEvent ) [inline, private]

Definition at line 216 of file time_sequencer.h.


Member Data Documentation

template<class M>
ros::Duration message_filters::TimeSequencer< M >::delay_ [private]

Definition at line 226 of file time_sequencer.h.

Definition at line 233 of file time_sequencer.h.

template<class M>
ros::Time message_filters::TimeSequencer< M >::last_time_ [private]

Definition at line 238 of file time_sequencer.h.

template<class M>
S_Message message_filters::TimeSequencer< M >::messages_ [private]

Definition at line 236 of file time_sequencer.h.

template<class M>
boost::mutex message_filters::TimeSequencer< M >::messages_mutex_ [private]

Definition at line 237 of file time_sequencer.h.

template<class M>
ros::NodeHandle message_filters::TimeSequencer< M >::nh_ [private]

Definition at line 229 of file time_sequencer.h.

template<class M>
uint32_t message_filters::TimeSequencer< M >::queue_size_ [private]

Definition at line 228 of file time_sequencer.h.

template<class M>
ros::Duration message_filters::TimeSequencer< M >::update_rate_ [private]

Definition at line 227 of file time_sequencer.h.

template<class M>
ros::Timer message_filters::TimeSequencer< M >::update_timer_ [private]

Definition at line 231 of file time_sequencer.h.


The documentation for this class was generated from the following file:


message_filters
Author(s): Josh Faust, Vijay Pradeep
autogenerated on Thu Jun 6 2019 21:10:34