35 #include <gtest/gtest.h>
43 const unsigned int NA = 9;
44 static const double dataA[
NA][2] = { { 0, 0},
62 for (
unsigned int i=0; i<
NA; i++)
66 deflated->channels_.resize(2);
67 deflated->channels_[0] =
dataA[i][0];
68 deflated->channels_[1] =
dataA[i][1];
85 for (
unsigned int i=0; i<
NA; i++)
90 deflated->header.stamp =
ros::Time(i+10,0);
93 deflated->channels_.resize(2);
94 deflated->channels_[0] =
dataA[i][0];
95 deflated->channels_[1] =
dataA[i][1];
108 vector<double> tol(2);
113 calibration_msgs::Interval interval = IntervalCalc::computeLatestInterval(signal, tol, max_step);
114 EXPECT_EQ(interval.start.sec, (
unsigned int) 6);
115 EXPECT_EQ(interval.end.sec, (
unsigned int) 8);
123 vector<double> tol(2);
128 calibration_msgs::Interval interval = IntervalCalc::computeLatestInterval(signal, tol, max_step);
129 EXPECT_EQ(interval.start.sec, (
unsigned int) 5);
130 EXPECT_EQ(interval.end.sec, (
unsigned int) 8);
138 vector<double> tol(2);
144 calibration_msgs::Interval interval = IntervalCalc::computeLatestInterval(signal, tol, max_step);
145 EXPECT_EQ(interval.start.sec, (
unsigned int) 8);
146 EXPECT_EQ(interval.end.sec, (
unsigned int) 8);
154 vector<double> tol(2);
159 calibration_msgs::Interval interval = IntervalCalc::computeLatestInterval(signal, tol, max_step);
160 EXPECT_EQ(interval.start.sec, (
unsigned int) 15);
161 EXPECT_EQ(interval.end.sec, (
unsigned int) 18);
164 int main(
int argc,
char **argv){
165 testing::InitGoogleTest(&argc, argv);
166 return RUN_ALL_TESTS();