Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 
00038 
00039 #include <vector>
00040 #include <string>
00041 #include <sstream>
00042 #include <gtest/gtest.h>
00043 
00044 #include "calibration_msgs/Interval.h"
00045 #include "interval_intersection/interval_intersection.hpp"
00046 
00047 using namespace std;
00048 using namespace interval_intersection;
00049 
00050 stringstream output_stream;
00051 typedef boost::function<void (const calibration_msgs::IntervalConstPtr &)> Input;
00052 vector<Input> inputs;
00053 
00054 void publish(const calibration_msgs::Interval &interval)
00055 {
00056   
00057   output_stream << "[" << interval.start << ", " << interval.end << "] ";
00058 }
00059 
00060 void input_interval(ros::Time start, ros::Time end, int input_num) {
00061   boost::shared_ptr<calibration_msgs::Interval> interval(new calibration_msgs::Interval());
00062   interval->start = start;
00063   interval->end = end;
00064   
00065   inputs[input_num](interval);
00066 }
00067 
00068 TEST(Intersection, testCase1)
00069 {
00070   
00071   IntervalIntersector intersector(&publish);
00072   int n = 3;
00073   for (int i=0; i<n; i++) {
00074     inputs.push_back(intersector.getNewInputStream());
00075   }
00076 
00077   
00078   typedef ros::Time T;
00079   input_interval(T(10), T(20), 0);
00080   input_interval(T(2), T(16), 1);
00081   input_interval(T(8), T(21), 2);
00082   input_interval(T(23), T(30), 0);
00083   input_interval(T(6), T(25), 1);
00084   input_interval(T(18), T(28), 2);
00085 
00086   string correct_answer = "[10.000000000, 16.000000000] [10.000000000, 20.000000000] [23.000000000, 23.000000000] [23.000000000, 25.000000000] ";
00087   EXPECT_EQ(output_stream.str(), correct_answer);
00088 }
00089 
00090 
00091 
00092 int main(int argc, char **argv){
00093   testing::InitGoogleTest(&argc, argv);
00094   return RUN_ALL_TESTS();
00095 }
00096 
00097