Filters consecutive messages with the same timestamp. Only the first message passes, all consecutive are dropped. It is templated on the message type to be filtered. More...
#include <update_filter.h>
Public Types | |
typedef ros::MessageEvent< M const > | EventType |
typedef boost::shared_ptr< M const > | MConstPtr |
Public Member Functions | |
template<class F > | |
void | connectInput (F &f) |
Connect to the output of another filter. More... | |
template<typename F > | |
UpdateFilter (F &f) | |
Construct the filter and connect to the output of another filter. More... | |
Private Member Functions | |
void | cb (const EventType &evt) |
Private Attributes | |
Connection | incoming_connection_ |
ros::Time | last_message_time_ |
Additional Inherited Members |
Filters consecutive messages with the same timestamp. Only the first message passes, all consecutive are dropped. It is templated on the message type to be filtered.
Definition at line 40 of file update_filter.h.
typedef ros::MessageEvent<M const> message_filters::UpdateFilter< M >::EventType |
Definition at line 44 of file update_filter.h.
typedef boost::shared_ptr<M const> message_filters::UpdateFilter< M >::MConstPtr |
Definition at line 43 of file update_filter.h.
|
inline |
Construct the filter and connect to the output of another filter.
Definition at line 50 of file update_filter.h.
|
inlineprivate |
Definition at line 67 of file update_filter.h.
|
inline |
Connect to the output of another filter.
Definition at line 59 of file update_filter.h.
|
private |
Definition at line 79 of file update_filter.h.
|
private |
Definition at line 81 of file update_filter.h.