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

Stores a time history of messages. More...

#include <cache.h>

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

List of all members.

Public Types

typedef ros::MessageEvent< M
const > 
EventType
typedef boost::shared_ptr< M
const > 
MConstPtr

Public Member Functions

void add (const MConstPtr &msg)
 Add a message to the cache, and pop off any elements that are too old. This method is registered with a data provider when connectTo is called.
void add (const EventType &evt)
 Add a message to the cache, and pop off any elements that are too old. This method is registered with a data provider when connectTo is called.
template<class F >
 Cache (F &f, unsigned int cache_size=1)
 Cache (unsigned int cache_size=1)
template<class F >
void connectInput (F &f)
MConstPtr getElemAfterTime (const ros::Time &time) const
 Grab the oldest element that occurs right after the specified time.
MConstPtr getElemBeforeTime (const ros::Time &time) const
 Grab the newest element that occurs right before the specified time.
std::vector< MConstPtrgetInterval (const ros::Time &start, const ros::Time &end) const
 Receive a vector of messages that occur between a start and end time (inclusive).
ros::Time getLatestTime () const
 Returns the timestamp associated with the newest packet cache.
ros::Time getOldestTime () const
 Returns the timestamp associated with the oldest packet cache.
std::vector< MConstPtrgetSurroundingInterval (const ros::Time &start, const ros::Time &end) const
 Retrieve the smallest interval of messages that surrounds an interval from start to end.
void setCacheSize (unsigned int cache_size)
 ~Cache ()

Private Member Functions

void callback (const EventType &evt)

Private Attributes

std::deque< EventTypecache_
 Cache for the messages.
boost::mutex cache_lock_
 Lock for cache_.
unsigned int cache_size_
 Maximum number of elements allowed in the cache.
Connection incoming_connection_

Detailed Description

template<class M>
class message_filters::Cache< M >

Stores a time history of messages.

Given a stream of messages, the most recent N messages are cached in a ring buffer, from which time intervals of the cache can then be retrieved by the client.

Cache immediately passes messages through to its output connections.

CONNECTIONS

Cache'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 66 of file cache.h.


Member Typedef Documentation

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

Reimplemented from message_filters::SimpleFilter< M >.

Definition at line 70 of file cache.h.

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

Reimplemented from message_filters::SimpleFilter< M >.

Definition at line 69 of file cache.h.


Constructor & Destructor Documentation

template<class M>
template<class F >
message_filters::Cache< M >::Cache ( F &  f,
unsigned int  cache_size = 1 
) [inline]

Definition at line 73 of file cache.h.

template<class M>
message_filters::Cache< M >::Cache ( unsigned int  cache_size = 1) [inline]

Initializes a Message Cache without specifying a parent filter. This implies that in order to populate the cache, the user then has to call add themselves, or connectInput() is called later

Definition at line 84 of file cache.h.

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

Definition at line 95 of file cache.h.


Member Function Documentation

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

Add a message to the cache, and pop off any elements that are too old. This method is registered with a data provider when connectTo is called.

Definition at line 119 of file cache.h.

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

Add a message to the cache, and pop off any elements that are too old. This method is registered with a data provider when connectTo is called.

Definition at line 128 of file cache.h.

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

Definition at line 328 of file cache.h.

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

Definition at line 90 of file cache.h.

template<class M>
MConstPtr message_filters::Cache< M >::getElemAfterTime ( const ros::Time time) const [inline]

Grab the oldest element that occurs right after the specified time.

Parameters:
timeTime that must occur right before the returned elem
Returns:
shared_ptr to the oldest elem that occurs after 'time'. NULL if doesn't exist

Definition at line 267 of file cache.h.

template<class M>
MConstPtr message_filters::Cache< M >::getElemBeforeTime ( const ros::Time time) const [inline]

Grab the newest element that occurs right before the specified time.

Parameters:
timeTime that must occur right after the returned elem
Returns:
shared_ptr to the newest elem that occurs before 'time'. NULL if doesn't exist

Definition at line 239 of file cache.h.

template<class M>
std::vector<MConstPtr> message_filters::Cache< M >::getInterval ( const ros::Time start,
const ros::Time end 
) const [inline]

Receive a vector of messages that occur between a start and end time (inclusive).

This call is non-blocking, and only aggregates messages it has already received. It will not wait for messages have not yet been received, but occur in the interval.

Parameters:
startThe start of the requested interval
endThe end of the requested interval

Definition at line 166 of file cache.h.

template<class M>
ros::Time message_filters::Cache< M >::getLatestTime ( ) const [inline]

Returns the timestamp associated with the newest packet cache.

Definition at line 295 of file cache.h.

template<class M>
ros::Time message_filters::Cache< M >::getOldestTime ( ) const [inline]

Returns the timestamp associated with the oldest packet cache.

Definition at line 312 of file cache.h.

template<class M>
std::vector<MConstPtr> message_filters::Cache< M >::getSurroundingInterval ( const ros::Time start,
const ros::Time end 
) const [inline]

Retrieve the smallest interval of messages that surrounds an interval from start to end.

If the messages in the cache do not surround (start,end), then this will return the interval that gets closest to surrounding (start,end)

Definition at line 205 of file cache.h.

template<class M>
void message_filters::Cache< M >::setCacheSize ( unsigned int  cache_size) [inline]

Set the size of the cache.

Parameters:
cache_sizeThe new size the cache should be. Must be > 0

Definition at line 104 of file cache.h.


Member Data Documentation

template<class M>
std::deque<EventType> message_filters::Cache< M >::cache_ [private]

Cache for the messages.

Definition at line 334 of file cache.h.

template<class M>
boost::mutex message_filters::Cache< M >::cache_lock_ [mutable, private]

Lock for cache_.

Definition at line 333 of file cache.h.

template<class M>
unsigned int message_filters::Cache< M >::cache_size_ [private]

Maximum number of elements allowed in the cache.

Definition at line 335 of file cache.h.

template<class M>
Connection message_filters::Cache< M >::incoming_connection_ [private]

Definition at line 337 of file cache.h.


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


message_filters
Author(s): Josh Faust, Vijay Pradeep
autogenerated on Tue Mar 7 2017 03:45:14