Classes | Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
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]

Classes

class  MessageSort
 

Public Types

typedef ros::MessageEvent< M const > EventType
 
typedef boost::shared_ptr< M const > MConstPtr
 
- Public Types inherited from message_filters::SimpleFilter< M >
typedef boost::function< void(const MConstPtr &)> Callback
 
typedef boost::function< void(const EventType &)> EventCallback
 
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 ()
 
- Public Member Functions inherited from message_filters::SimpleFilter< M >
const std::string & getName ()
 Get the name of this filter. For debugging use. More...
 
template<typename P >
Connection registerCallback (const boost::function< void(P)> &callback)
 Register a callback to be called when this filter has passed. More...
 
template<typename C >
Connection registerCallback (const C &callback)
 Register a callback to be called when this filter has passed. More...
 
template<typename P >
Connection registerCallback (void(*callback)(P))
 Register a callback to be called when this filter has passed. More...
 
template<typename T , typename P >
Connection registerCallback (void(T::*callback)(P), T *t)
 Register a callback to be called when this filter has passed. More...
 
void setName (const std::string &name)
 Set the name of this filter. For debugging use. More...
 

Private Types

typedef std::multiset< EventType, MessageSortS_Message
 
typedef std::vector< EventTypeV_Message
 

Private Member Functions

void cb (const EventType &evt)
 
void dispatch ()
 
void init ()
 
void update (const ros::SteadyTimerEvent &)
 

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::SteadyTimer update_timer_
 

Additional Inherited Members

- Protected Member Functions inherited from message_filters::SimpleFilter< M >
void signalMessage (const MConstPtr &msg)
 Call all registered callbacks, passing them the specified message. More...
 
void signalMessage (const ros::MessageEvent< M const > &event)
 Call all registered callbacks, passing them the specified message. More...
 

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 107 of file time_sequencer.h.

Member Typedef Documentation

◆ EventType

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

Definition at line 111 of file time_sequencer.h.

◆ MConstPtr

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

Definition at line 110 of file time_sequencer.h.

◆ S_Message

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

Definition at line 204 of file time_sequencer.h.

◆ V_Message

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

Definition at line 205 of file time_sequencer.h.

Constructor & Destructor Documentation

◆ TimeSequencer() [1/2]

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::SteadyTimer that runs at update_rate

Definition at line 122 of file time_sequencer.h.

◆ TimeSequencer() [2/2]

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::SteadyTimer that runs at update_rate

Definition at line 142 of file time_sequencer.h.

◆ ~TimeSequencer()

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

Definition at line 161 of file time_sequencer.h.

Member Function Documentation

◆ add() [1/2]

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

Definition at line 167 of file time_sequencer.h.

◆ add() [2/2]

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

Manually add a message to the cache.

Definition at line 188 of file time_sequencer.h.

◆ cb()

template<class M >
void message_filters::TimeSequencer< M >::cb ( const EventType evt)
inlineprivate

Definition at line 207 of file time_sequencer.h.

◆ connectInput()

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 155 of file time_sequencer.h.

◆ dispatch()

template<class M >
void message_filters::TimeSequencer< M >::dispatch ( )
inlineprivate

Definition at line 212 of file time_sequencer.h.

◆ init()

template<class M >
void message_filters::TimeSequencer< M >::init ( )
inlineprivate

Definition at line 253 of file time_sequencer.h.

◆ update()

template<class M >
void message_filters::TimeSequencer< M >::update ( const ros::SteadyTimerEvent )
inlineprivate

Definition at line 248 of file time_sequencer.h.

Member Data Documentation

◆ delay_

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

Definition at line 258 of file time_sequencer.h.

◆ incoming_connection_

template<class M >
Connection message_filters::TimeSequencer< M >::incoming_connection_
private

Definition at line 265 of file time_sequencer.h.

◆ last_time_

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

Definition at line 270 of file time_sequencer.h.

◆ messages_

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

Definition at line 268 of file time_sequencer.h.

◆ messages_mutex_

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

Definition at line 269 of file time_sequencer.h.

◆ nh_

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

Definition at line 261 of file time_sequencer.h.

◆ queue_size_

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

Definition at line 260 of file time_sequencer.h.

◆ update_rate_

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

Definition at line 259 of file time_sequencer.h.

◆ update_timer_

template<class M >
ros::SteadyTimer message_filters::TimeSequencer< M >::update_timer_
private

Definition at line 263 of file time_sequencer.h.


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


message_filters
Author(s): Josh Faust, Vijay Pradeep, Dirk Thomas , Jacob Perron
autogenerated on Thu Nov 23 2023 04:01:54