Stores a time history of messages. More...
#include <cache.h>
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< MConstPtr > | getInterval (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< MConstPtr > | getSurroundingInterval (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< EventType > | cache_ |
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_ |
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.
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>&);
typedef ros::MessageEvent<M const> message_filters::Cache< M >::EventType |
Reimplemented from message_filters::SimpleFilter< M >.
typedef boost::shared_ptr<M const> message_filters::Cache< M >::MConstPtr |
Reimplemented from message_filters::SimpleFilter< M >.
message_filters::Cache< M >::Cache | ( | F & | f, |
unsigned int | cache_size = 1 |
||
) | [inline] |
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
message_filters::Cache< M >::~Cache | ( | ) | [inline] |
void message_filters::Cache< M >::add | ( | const MConstPtr & | msg | ) | [inline] |
void message_filters::Cache< M >::add | ( | const EventType & | evt | ) | [inline] |
void message_filters::Cache< M >::callback | ( | const EventType & | evt | ) | [inline, private] |
void message_filters::Cache< M >::connectInput | ( | F & | f | ) | [inline] |
MConstPtr message_filters::Cache< M >::getElemAfterTime | ( | const ros::Time & | time | ) | const [inline] |
MConstPtr message_filters::Cache< M >::getElemBeforeTime | ( | const ros::Time & | time | ) | const [inline] |
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.
start | The start of the requested interval |
end | The end of the requested interval |
ros::Time message_filters::Cache< M >::getLatestTime | ( | ) | const [inline] |
ros::Time message_filters::Cache< M >::getOldestTime | ( | ) | const [inline] |
std::vector<MConstPtr> message_filters::Cache< M >::getSurroundingInterval | ( | const ros::Time & | start, |
const ros::Time & | end | ||
) | const [inline] |
void message_filters::Cache< M >::setCacheSize | ( | unsigned int | cache_size | ) | [inline] |
std::deque<EventType> message_filters::Cache< M >::cache_ [private] |
boost::mutex message_filters::Cache< M >::cache_lock_ [mutable, private] |
unsigned int message_filters::Cache< M >::cache_size_ [private] |
Connection message_filters::Cache< M >::incoming_connection_ [private] |