Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
interval_intersection::IntervalIntersector Class Reference

#include <interval_intersection.hpp>

Classes

struct  queue_stat
 

Public Member Functions

calibration_msgs::IntervalStatus get_status ()
 
boost::function< void(const calibration_msgs::IntervalConstPtr &)> getNewInputStream ()
 
 IntervalIntersector (boost::function< void(const calibration_msgs::Interval &)> output_callback)
 
 ~IntervalIntersector ()
 

Private Member Functions

void inputCallback (const calibration_msgs::IntervalConstPtr &interval_ptr, size_t i)
 Interval message callback. More...
 
void process_queues ()
 

Private Attributes

size_t max_queue_size
 
vector< boost::shared_ptr< boost::mutex > > mutexes
 
boost::function< void(const calibration_msgs::Interval &)> output_callback_
 
boost::mutex processing_mutex
 
vector< boost::shared_ptr< queue_stat > > queue_stats
 
vector< deque< calibration_msgs::IntervalConstPtr > > queues
 

Detailed Description

IntervalIntersector

This class receives streams of interval messages, sorted by end time within each stream. For each end time, it outputs the largest intervals contained in one interval of each stream. This class is general, but is designed to compute the intervals of time where a list of sensors were all stable at the same time, and can therefore be used together for calibration. The code assumes that start times of intervals are also non-decreasing. If not, it will output a reasonable answer though not an optimal one (it is impossible in that case to guarantee optimality since a later message can extend a previously output interval).

Definition at line 60 of file interval_intersection.hpp.

Constructor & Destructor Documentation

◆ IntervalIntersector()

IntervalIntersector::IntervalIntersector ( boost::function< void(const calibration_msgs::Interval &)>  output_callback)

Definition at line 50 of file interval_intersection.cpp.

◆ ~IntervalIntersector()

IntervalIntersector::~IntervalIntersector ( )

Definition at line 56 of file interval_intersection.cpp.

Member Function Documentation

◆ get_status()

calibration_msgs::IntervalStatus IntervalIntersector::get_status ( )

Definition at line 167 of file interval_intersection.cpp.

◆ getNewInputStream()

boost::function< void(const calibration_msgs::IntervalConstPtr &)> IntervalIntersector::getNewInputStream ( )

Definition at line 62 of file interval_intersection.cpp.

◆ inputCallback()

void IntervalIntersector::inputCallback ( const calibration_msgs::IntervalConstPtr &  interval_ptr,
size_t  i 
)
private

Interval message callback.

It puts the message on a queue. If all queues are non-empty, they are processed until one of them is empty.

Definition at line 87 of file interval_intersection.cpp.

◆ process_queues()

void IntervalIntersector::process_queues ( )
private

Definition at line 102 of file interval_intersection.cpp.

Member Data Documentation

◆ max_queue_size

size_t interval_intersection::IntervalIntersector::max_queue_size
private

Definition at line 88 of file interval_intersection.hpp.

◆ mutexes

vector<boost::shared_ptr<boost::mutex> > interval_intersection::IntervalIntersector::mutexes
private

Definition at line 86 of file interval_intersection.hpp.

◆ output_callback_

boost::function<void (const calibration_msgs::Interval&)> interval_intersection::IntervalIntersector::output_callback_
private

Definition at line 89 of file interval_intersection.hpp.

◆ processing_mutex

boost::mutex interval_intersection::IntervalIntersector::processing_mutex
private

Definition at line 87 of file interval_intersection.hpp.

◆ queue_stats

vector<boost::shared_ptr<queue_stat> > interval_intersection::IntervalIntersector::queue_stats
private

Definition at line 85 of file interval_intersection.hpp.

◆ queues

vector<deque<calibration_msgs::IntervalConstPtr> > interval_intersection::IntervalIntersector::queues
private

Definition at line 84 of file interval_intersection.hpp.


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


interval_intersection
Author(s): Romain Thibaux
autogenerated on Tue Mar 1 2022 23:58:50