#include <trigger_matcher.h>
Public Types | |
typedef std::pair< ros::Time, boost::shared_ptr< C const > > | DataPair |
typedef boost::function< void(const ros::Time &, boost::shared_ptr< C const > &)> | MatchCallback |
Public Member Functions | |
void | dataCallback (double stamp, const C &data) |
void | dataCallback (const ros::Time &stamp, const C &data) |
void | dataCallback (double stamp, const boost::shared_ptr< C const > &data) |
void | dataCallback (const ros::Time &stamp, const boost::shared_ptr< C const > &data) |
void | dataCallback (const DataPair &pair) |
QueuedTriggerMatcher (unsigned int late_data_count_allowed, unsigned int max_trig_queue_length, unsigned int max_data_queue_length) | |
void | reset () |
void | setMatchCallback (MatchCallback &cb) |
virtual | ~QueuedTriggerMatcher () |
Public Member Functions inherited from timestamp_tools::TriggerMatcherBase | |
bool | hasTimestamp () |
void | setLateDataCountAllowed (unsigned int v) |
void | setTrigDelay (double delay) |
void | setTrigDelay (const ros::Duration &delay) |
void | triggerCallback (double stamp) |
void | triggerCallback (const std_msgs::HeaderConstPtr &msg) |
void | triggerCallback (const ros::Time &stamp) |
TriggerMatcherBase (unsigned int late_data_count_allowed, unsigned int max_trig_queue_length) | |
virtual | ~TriggerMatcherBase () |
Protected Member Functions | |
virtual void | gotTrigger () |
Protected Member Functions inherited from timestamp_tools::TriggerMatcherBase | |
virtual void | baseReset () |
ros::Time | getTimestampNoblockPrelocked (const ros::Time &data_time) |
Static Private Member Functions | |
static void | DefaultCallback (const ros::Time &t, boost::shared_ptr< C const > &d) |
Private Attributes | |
std::queue< DataPair > | data_queue_ |
MatchCallback | match_callback_ |
unsigned int | max_data_queue_length_ |
Additional Inherited Members | |
Public Attributes inherited from timestamp_tools::TriggerMatcherBase | |
bool | verbose_ |
Static Public Attributes inherited from timestamp_tools::TriggerMatcherBase | |
static const ros::Time | DropData = ros::TIME_MIN |
static const ros::Time | RetryLater = ros::TIME_MAX |
Protected Attributes inherited from timestamp_tools::TriggerMatcherBase | |
boost::mutex | mutex_ |
Definition at line 284 of file trigger_matcher.h.
typedef std::pair<ros::Time, boost::shared_ptr<C const> > timestamp_tools::QueuedTriggerMatcher< C >::DataPair |
Definition at line 287 of file trigger_matcher.h.
typedef boost::function<void(const ros::Time &, boost::shared_ptr<C const> &)> timestamp_tools::QueuedTriggerMatcher< C >::MatchCallback |
Definition at line 288 of file trigger_matcher.h.
|
inlinevirtual |
Definition at line 321 of file trigger_matcher.h.
|
inline |
Definition at line 330 of file trigger_matcher.h.
|
inline |
Definition at line 337 of file trigger_matcher.h.
|
inline |
Definition at line 342 of file trigger_matcher.h.
|
inline |
Definition at line 348 of file trigger_matcher.h.
|
inline |
Definition at line 353 of file trigger_matcher.h.
|
inline |
Definition at line 366 of file trigger_matcher.h.
|
inlinestaticprivate |
Definition at line 295 of file trigger_matcher.h.
|
inlineprotectedvirtual |
Implements timestamp_tools::TriggerMatcherBase.
Definition at line 301 of file trigger_matcher.h.
|
inline |
Definition at line 358 of file trigger_matcher.h.
|
inline |
Definition at line 325 of file trigger_matcher.h.
|
private |
Definition at line 292 of file trigger_matcher.h.
|
private |
Definition at line 291 of file trigger_matcher.h.
|
private |
Definition at line 293 of file trigger_matcher.h.