laser_interval_calc_unittest.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #include <gtest/gtest.h>
36 
38 
39 using namespace std;
40 using namespace laser_cb_detector;
41 
42 static const bool DEBUG=false;
43 
44 static const float eps = 1e-6;
45 
46 class LaserIntervalCalcTest : public ::testing::Test
47 {
48 protected:
49  virtual void SetUp()
50  {
51  snapshot_.header.stamp = ros::Time(10,0);
52  snapshot_.time_increment = 1.0;
53  snapshot_.readings_per_scan = 4;
54  snapshot_.num_scans = 3;
55  snapshot_.scan_start.resize(3);
56  snapshot_.scan_start[0] = ros::Time(20);
57  snapshot_.scan_start[1] = ros::Time(40);
58  snapshot_.scan_start[2] = ros::Time(30);
59 
60  // Snapshot Times:
61  // 20 21 22 23 24
62  // 40 41 42 43 44
63  // 30 31 32 33 34
64  }
65 
66  calibration_msgs::DenseLaserSnapshot snapshot_;
67  calibration_msgs::CalibrationPattern features_;
68  calibration_msgs::Interval interval_;
69 };
70 
71 #define EXPECT_ROSTIME_NEAR(a, b) \
72  EXPECT_NEAR( (a-b).toSec(), 0.0, eps) \
73  << "Times don't match: #a: " << a.toSec() << " " << "#b: " << b.toSec()
74 
75 TEST_F(LaserIntervalCalcTest, easy_single_point)
76 {
77  bool success;
78  features_.image_points.resize(1);
79  features_.image_points[0].x = .5;
80  features_.image_points[0].y = 1.5;
81  success = LaserIntervalCalc::computeInterval(snapshot_, features_, interval_);
82  EXPECT_TRUE(success);
83  EXPECT_ROSTIME_NEAR(interval_.start, ros::Time(30,0));
84  EXPECT_ROSTIME_NEAR(interval_.end, ros::Time(41,0));
85 }
86 
88 {
89  bool success;
90  features_.image_points.resize(1);
91  features_.image_points[0].x = .5;
92  features_.image_points[0].y = 0.01;
93  success = LaserIntervalCalc::computeInterval(snapshot_, features_, interval_);
94  EXPECT_TRUE(success);
95  EXPECT_ROSTIME_NEAR(interval_.start, ros::Time(20,0));
96  EXPECT_ROSTIME_NEAR(interval_.end, ros::Time(41,0));
97 
98  features_.image_points[0].y = -0.01;
99  success = LaserIntervalCalc::computeInterval(snapshot_, features_, interval_);
100  EXPECT_FALSE(success);
101 
102  features_.image_points[0].y = 2.01;
103  success = LaserIntervalCalc::computeInterval(snapshot_, features_, interval_);
104  EXPECT_FALSE(success);
105 }
106 
108 {
109  bool success;
110  features_.image_points.clear();
111  success = LaserIntervalCalc::computeInterval(snapshot_, features_, interval_);
112  EXPECT_TRUE(success);
113  EXPECT_ROSTIME_NEAR(interval_.start, ros::Time(10,0));
114  EXPECT_ROSTIME_NEAR(interval_.end, ros::Time(10,0));
115 }
116 
117 TEST_F(LaserIntervalCalcTest, easy_multi_point)
118 {
119  bool success;
120  features_.image_points.resize(3);
121  features_.image_points[0].x = .5;
122  features_.image_points[0].y = .5;
123  features_.image_points[1].x = 3.5;
124  features_.image_points[1].y = .5;
125  features_.image_points[2].x = 3.5;
126  features_.image_points[2].y = 1.5;
127 
128  success = LaserIntervalCalc::computeInterval(snapshot_, features_, interval_);
129  EXPECT_TRUE(success);
130  EXPECT_ROSTIME_NEAR(interval_.start, ros::Time(20,0));
131  EXPECT_ROSTIME_NEAR(interval_.end, ros::Time(44,0));
132 }
133 
134 int main(int argc, char **argv)
135 {
136  testing::InitGoogleTest(&argc, argv);
137  return RUN_ALL_TESTS();
138 }
#define EXPECT_ROSTIME_NEAR(a, b)
int main(int argc, char **argv)
static const float eps
TEST_F(LaserIntervalCalcTest, easy_single_point)
calibration_msgs::CalibrationPattern features_
static const bool DEBUG
calibration_msgs::Interval interval_
calibration_msgs::DenseLaserSnapshot snapshot_


laser_cb_detector
Author(s): Vijay Pradeep
autogenerated on Thu Jun 6 2019 19:17:28