Public Types | Public Member Functions | Protected Member Functions | Static Private Member Functions | Private Attributes | List of all members
timestamp_tools::QueuedTriggerMatcher< C > Class Template Reference

#include <trigger_matcher.h>

Inheritance diagram for timestamp_tools::QueuedTriggerMatcher< C >:
Inheritance graph
[legend]

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 (const DataPair &pair)
 
void dataCallback (const ros::Time &stamp, const boost::shared_ptr< C const > &data)
 
void dataCallback (const ros::Time &stamp, const C &data)
 
void dataCallback (double stamp, const boost::shared_ptr< C const > &data)
 
void dataCallback (double stamp, const C &data)
 
 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 (const ros::Duration &delay)
 
void setTrigDelay (double delay)
 
void triggerCallback (const ros::Time &stamp)
 
void triggerCallback (const std_msgs::HeaderConstPtr &msg)
 
void triggerCallback (double 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< DataPairdata_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_
 

Detailed Description

template<class C>
class timestamp_tools::QueuedTriggerMatcher< C >

Definition at line 316 of file trigger_matcher.h.

Member Typedef Documentation

◆ DataPair

template<class C >
typedef std::pair<ros::Time, boost::shared_ptr<C const> > timestamp_tools::QueuedTriggerMatcher< C >::DataPair

Definition at line 319 of file trigger_matcher.h.

◆ MatchCallback

template<class C >
typedef boost::function<void(const ros::Time &, boost::shared_ptr<C const> &)> timestamp_tools::QueuedTriggerMatcher< C >::MatchCallback

Definition at line 320 of file trigger_matcher.h.

Constructor & Destructor Documentation

◆ ~QueuedTriggerMatcher()

template<class C >
virtual timestamp_tools::QueuedTriggerMatcher< C >::~QueuedTriggerMatcher ( )
inlinevirtual

Definition at line 353 of file trigger_matcher.h.

◆ QueuedTriggerMatcher()

template<class C >
timestamp_tools::QueuedTriggerMatcher< C >::QueuedTriggerMatcher ( unsigned int  late_data_count_allowed,
unsigned int  max_trig_queue_length,
unsigned int  max_data_queue_length 
)
inline

Definition at line 362 of file trigger_matcher.h.

Member Function Documentation

◆ dataCallback() [1/5]

template<class C >
void timestamp_tools::QueuedTriggerMatcher< C >::dataCallback ( const DataPair pair)
inline

Definition at line 398 of file trigger_matcher.h.

◆ dataCallback() [2/5]

template<class C >
void timestamp_tools::QueuedTriggerMatcher< C >::dataCallback ( const ros::Time stamp,
const boost::shared_ptr< C const > &  data 
)
inline

Definition at line 385 of file trigger_matcher.h.

◆ dataCallback() [3/5]

template<class C >
void timestamp_tools::QueuedTriggerMatcher< C >::dataCallback ( const ros::Time stamp,
const C &  data 
)
inline

Definition at line 374 of file trigger_matcher.h.

◆ dataCallback() [4/5]

template<class C >
void timestamp_tools::QueuedTriggerMatcher< C >::dataCallback ( double  stamp,
const boost::shared_ptr< C const > &  data 
)
inline

Definition at line 380 of file trigger_matcher.h.

◆ dataCallback() [5/5]

template<class C >
void timestamp_tools::QueuedTriggerMatcher< C >::dataCallback ( double  stamp,
const C &  data 
)
inline

Definition at line 369 of file trigger_matcher.h.

◆ DefaultCallback()

template<class C >
static void timestamp_tools::QueuedTriggerMatcher< C >::DefaultCallback ( const ros::Time t,
boost::shared_ptr< C const > &  d 
)
inlinestaticprivate

Definition at line 327 of file trigger_matcher.h.

◆ gotTrigger()

template<class C >
virtual void timestamp_tools::QueuedTriggerMatcher< C >::gotTrigger ( )
inlineprotectedvirtual

Implements timestamp_tools::TriggerMatcherBase.

Definition at line 333 of file trigger_matcher.h.

◆ reset()

template<class C >
void timestamp_tools::QueuedTriggerMatcher< C >::reset ( )
inline

Definition at line 390 of file trigger_matcher.h.

◆ setMatchCallback()

template<class C >
void timestamp_tools::QueuedTriggerMatcher< C >::setMatchCallback ( MatchCallback cb)
inline

Definition at line 357 of file trigger_matcher.h.

Member Data Documentation

◆ data_queue_

template<class C >
std::queue<DataPair> timestamp_tools::QueuedTriggerMatcher< C >::data_queue_
private

Definition at line 324 of file trigger_matcher.h.

◆ match_callback_

template<class C >
MatchCallback timestamp_tools::QueuedTriggerMatcher< C >::match_callback_
private

Definition at line 323 of file trigger_matcher.h.

◆ max_data_queue_length_

template<class C >
unsigned int timestamp_tools::QueuedTriggerMatcher< C >::max_data_queue_length_
private

Definition at line 325 of file trigger_matcher.h.


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


timestamp_tools
Author(s): Blaise Gassend
autogenerated on Wed Mar 2 2022 00:11:51