35 #ifndef __TIMESTAMP_TOOLS__TRIGGER_MATCHER_H__ 36 #define __TIMESTAMP_TOOLS__TRIGGER_MATCHER_H__ 41 #include <boost/thread.hpp> 42 #include <boost/thread/condition.hpp> 43 #include <std_msgs/Header.h> 44 #include <boost/thread/thread_time.hpp> 64 ROS_WARN(
"TriggerMatcherBase: data arrived before trigger. Discarding data sample.");
105 ROS_WARN(
"TriggerMatcherBase: too many late data packets. Assuming missed trigger. Relocking...");
144 return trig_queue_.front() > data_stamp;
155 return !trig_queue_.empty();
164 late_data_count_allowed_ = v;
179 last_data_stamp_(
ros::TIME_MIN),
180 late_data_count_allowed_(late_data_count_allowed),
182 max_trig_queue_length_(max_trig_queue_length),
183 synchronized_(false),
200 boost::mutex::scoped_lock(mutex_);
202 trig_queue_.push(stamp + trig_delay_);
206 ROS_WARN(
"TriggerMatcherBase: trig_queue_ overflow dropping from front.");
225 got_trigger_condition_.notify_one();
232 TriggerMatcher(
unsigned int late_data_count_allowed,
unsigned int max_trig_queue_length) :
238 boost::mutex::scoped_lock lock(
mutex_);
240 got_trigger_condition_.notify_all();
246 boost::mutex::scoped_lock data_lock(data_source_mutex_);
247 boost::mutex::scoped_lock lock(
mutex_);
254 got_trigger_condition_.wait(lock);
261 boost::mutex::scoped_lock data_lock(data_source_mutex_);
262 boost::mutex::scoped_lock lock(
mutex_);
269 got_trigger_condition_.timed_wait(lock, boost::posix_time::microseconds((
int) (timeout * 1e6)));
276 boost::mutex::scoped_lock data_lock(data_source_mutex_);
277 boost::mutex::scoped_lock lock(
mutex_);
287 typedef std::pair<ros::Time, boost::shared_ptr<C const> >
DataPair;
288 typedef boost::function<void(const ros::Time &, boost::shared_ptr<C const> &)>
MatchCallback;
297 ROS_ERROR(
"QueuedTriggerMatcher triggered with no callback set. This is a bug in the code that uses QueuedTriggerMatcher.");
303 while (!data_queue_.empty())
305 DataPair &data = data_queue_.front();
314 match_callback_(stamp, data.second);
327 match_callback_ = cb;
330 QueuedTriggerMatcher(
unsigned int late_data_count_allowed,
unsigned int max_trig_queue_length,
unsigned int max_data_queue_length) :
332 max_data_queue_length_(max_data_queue_length)
345 dataCallback(stamp, ptr);
355 dataCallback(DataPair(stamp, data));
360 boost::mutex::scoped_lock lock(
mutex_);
362 data_queue_ = std::queue<DataPair>();
368 boost::mutex::scoped_lock lock(
mutex_);
370 data_queue_.push(pair);
371 if (data_queue_.size() > max_data_queue_length_)
374 ROS_WARN(
"QueuedTriggerMatcher: trig_queue_ overflow dropping from front.");
383 #endif // __TIMESTAMP_TOOLS__TRIGGER_MATCHER_H__
const Time TIME_MIN(0, 1)
ROSTIME_DECL const Time TIME_MAX