laser_cb_detector_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 
37 
38 #include <laser_cb_detector/ConfigGoal.h>
40 #include <opencv/highgui.h>
41 
42 using namespace laser_cb_detector;
43 using namespace std;
44 
45 static const double pix_eps_ = .6 ;
46 static const double eps = 1e-6;
47 
48 static const bool DEBUG=false;
49 
50 // The path to our test data comes in from CMake as TEST_PATH;
51 // stringify it and stuff it into a variable for later use.
52 #define xstr(s) str(s)
53 #define str(s) #s
54 static const string test_path = xstr(TEST_PATH);
55 
56 calibration_msgs::DenseLaserSnapshot getSnapshot(const string& filename)
57 {
58  IplImage* image;
59  image = cvLoadImage(filename.c_str(), 0); // 0 -> Force image to grayscale
60  EXPECT_TRUE(image) << "could not open image file [" << filename << "]" << endl;
61 
62 
63  IplImage* float_image;
64  float_image = cvCreateImage( cvSize(image->width, image->height), IPL_DEPTH_32F, 1);
65  cvConvert(image, float_image);
66 
67  calibration_msgs::DenseLaserSnapshot snapshot;
68  snapshot.readings_per_scan = image->width;
69  snapshot.num_scans = image->height;
70  snapshot.intensities.resize(image->height * image->width);
71 
72  for (int i=0; i<float_image->height; i++)
73  {
74  memcpy(&snapshot.intensities[i*snapshot.readings_per_scan],
75  (float_image->imageData + i*float_image->widthStep),
76  sizeof(float)*snapshot.readings_per_scan);
77  }
78 
79  if (DEBUG)
80  {
81  for (unsigned int i=0; i<snapshot.num_scans; i++)
82  {
83  for (unsigned int j=0; j<snapshot.readings_per_scan; j++)
84  {
85  if (snapshot.intensities[i*snapshot.readings_per_scan + j] < 100.0)
86  printf(" ");
87  else
88  printf("X");
89  }
90  printf("\n");
91  }
92  }
93 
94  cvReleaseImage(&float_image);
95  cvReleaseImage(&image);
96 
97  return snapshot;
98 }
99 
100 ConfigGoal config3x4()
101 {
102  ConfigGoal config;
103 
104  config.num_x = 3;
105  config.num_y = 4;
106  config.spacing_x = 1.0;
107  config.spacing_y = 1.0;
108 
109  config.width_scaling = 1.0;
110  config.height_scaling = 1.0;
111 
112  config.min_intensity = 0.0;
113  config.max_intensity = 100.0;
114 
115  config.subpixel_window = 3;
116  config.subpixel_zero_zone = 1;
117 
118  config.flip_horizontal = 0;
119 
120  return config;
121 }
122 
123 
124 void check3x4(const calibration_msgs::CalibrationPattern& result, double pix_eps, bool flipped)
125 {
126  EXPECT_TRUE(result.success);
127 
128 
129  EXPECT_NEAR(result.object_points[0].x, 0.0, eps);
130  EXPECT_NEAR(result.object_points[0].y, 0.0, eps);
131  EXPECT_NEAR(result.object_points[0].z, 0.0, eps);
132 
133  EXPECT_NEAR(result.object_points[2].x, 2.0, eps);
134  EXPECT_NEAR(result.object_points[2].y, 0.0, eps);
135  EXPECT_NEAR(result.object_points[2].z, 0.0, eps);
136 
137  EXPECT_NEAR(result.object_points[5].x, 2.0, eps);
138  EXPECT_NEAR(result.object_points[5].y, 1.0, eps);
139  EXPECT_NEAR(result.object_points[5].z, 0.0, eps);
140 
141  // Detected corners
142  if (flipped)
143  {
144  EXPECT_NEAR(result.image_points[0].x, 81.5, pix_eps);
145  EXPECT_NEAR(result.image_points[0].y, 72.0, pix_eps);
146 
147  EXPECT_NEAR(result.image_points[1].x, 81.5, pix_eps);
148  EXPECT_NEAR(result.image_points[1].y, 118.5, pix_eps);
149 
150  EXPECT_NEAR(result.image_points[11].x, 223.5, pix_eps);
151  EXPECT_NEAR(result.image_points[11].y, 166.5, pix_eps);
152  }
153  else
154  {
155  EXPECT_NEAR(result.image_points[0].x, 223.0, pix_eps);
156  EXPECT_NEAR(result.image_points[0].y, 72.0, pix_eps);
157 
158  EXPECT_NEAR(result.image_points[1].x, 223.0, pix_eps);
159  EXPECT_NEAR(result.image_points[1].y, 119.0, pix_eps);
160 
161  EXPECT_NEAR(result.image_points[11].x, 81.0, pix_eps);
162  EXPECT_NEAR(result.image_points[11].y, 166.0, pix_eps);
163  }
164 }
165 
166 TEST(LaserCbDetector, easy_cb_3x4)
167 {
168  LaserCbDetector detector;
169  calibration_msgs::DenseLaserSnapshot snapshot;
170 
171  snapshot = getSnapshot( test_path + "/data/cb_3x4.png");
172 
173  ASSERT_EQ(snapshot.readings_per_scan, (unsigned int) 303);
174  ASSERT_EQ(snapshot.num_scans, (unsigned int) 325);
175 
176  detector.configure(config3x4());
177 
178  bool return_result;
179  calibration_msgs::CalibrationPattern result;
180  return_result = detector.detect(snapshot, result);
181  EXPECT_TRUE(return_result);
182 
183  check3x4(result, pix_eps_, false);
184 }
185 
186 TEST(LaserCbDetector, scaled_cb_3x4)
187 {
188  LaserCbDetector detector;
189  calibration_msgs::DenseLaserSnapshot snapshot;
190 
191  snapshot = getSnapshot( test_path + "/data/cb_3x4.png");
192 
193  ASSERT_EQ(snapshot.readings_per_scan, (unsigned int) 303);
194  ASSERT_EQ(snapshot.num_scans, (unsigned int) 325);
195 
196  ConfigGoal config = config3x4();
197  config.width_scaling = 2.0;
198  config.height_scaling = 4.0;
199  detector.configure(config);
200 
201  bool return_result;
202  calibration_msgs::CalibrationPattern result;
203  return_result = detector.detect(snapshot, result);
204  EXPECT_TRUE(return_result);
205 
207  check3x4(result, 1.0, false);
208 }
209 
210 TEST(LaserCbDetector, reflected_cb_3x4)
211 {
212  LaserCbDetector detector;
213  calibration_msgs::DenseLaserSnapshot snapshot;
214 
215  snapshot = getSnapshot( test_path + "/data/cb_3x4.png");
216 
217  ASSERT_EQ(snapshot.readings_per_scan, (unsigned int) 303);
218  ASSERT_EQ(snapshot.num_scans, (unsigned int) 325);
219 
220  ConfigGoal config = config3x4();
221  config.flip_horizontal = 1;
222  detector.configure(config);
223 
224  bool return_result;
225  calibration_msgs::CalibrationPattern result;
226  return_result = detector.detect(snapshot, result);
227  EXPECT_TRUE(return_result);
228 
230  check3x4(result, 1.0, true);
231 }
232 
233 
234 TEST(LaserCbDetector, malformedTest)
235 {
236  LaserCbDetector detector;
237 
238  calibration_msgs::DenseLaserSnapshot snapshot;
239 
240  detector.configure(config3x4());
241  snapshot = getSnapshot( test_path + "/data/cb_3x4.png");
242  snapshot.num_scans = 10;
243 
244  bool return_result;
245  calibration_msgs::CalibrationPattern result;
246  return_result = detector.detect(snapshot, result);
247 
248  EXPECT_FALSE(return_result);
249 }
250 
251 TEST(LaserCbDetector, noCheckerboardTest)
252 {
253  LaserCbDetector detector;
254 
255  calibration_msgs::DenseLaserSnapshot snapshot;
256 
257  ConfigGoal config = config3x4();
258  config.num_x = 4;
259  detector.configure(config);
260  snapshot = getSnapshot( test_path + "/data/cb_3x4.png");
261 
262  bool return_result;
263  calibration_msgs::CalibrationPattern result;
264  return_result = detector.detect(snapshot, result);
265 
266  EXPECT_TRUE(return_result);
267  EXPECT_FALSE(result.success);
268 }
269 
270 
271 
272 int main(int argc, char **argv){
273  testing::InitGoogleTest(&argc, argv);
274  return RUN_ALL_TESTS();
275 }
bool detect(const calibration_msgs::DenseLaserSnapshot &snapshot, calibration_msgs::CalibrationPattern &result)
calibration_msgs::DenseLaserSnapshot getSnapshot(const string &filename)
#define xstr(s)
static const bool DEBUG
ConfigGoal config3x4()
static const string test_path
static const double eps
void check3x4(const calibration_msgs::CalibrationPattern &result, double pix_eps, bool flipped)
int main(int argc, char **argv)
static const double pix_eps_
TEST(LaserCbDetector, easy_cb_3x4)
bool configure(const ConfigGoal &config)


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