cv_laser_bridge_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 <calibration_msgs/DenseLaserSnapshot.h>
40 
41 using namespace std;
42 using namespace laser_cb_detector;
43 
44 static const bool DEBUG=false;
45 
46 calibration_msgs::DenseLaserSnapshot buildSnapshot(double start_range, double start_intensity, double increment,
47  const unsigned int H, const unsigned int W)
48 {
49  calibration_msgs::DenseLaserSnapshot snapshot;
50 
51  snapshot.readings_per_scan = W;
52  snapshot.num_scans = H;
53 
54  snapshot.ranges.resize(H*W);
55  snapshot.intensities.resize(H*W);
56 
57  for (unsigned int i=0; i<H*W; i++)
58  {
59  snapshot.ranges[i] = start_range + i*increment;
60  snapshot.intensities[i] = start_intensity + i*increment;
61  }
62 
63  return snapshot;
64 }
65 
66 static const unsigned int NUM_SCANS = 5;
67 static const unsigned int RAYS_PER_SCAN = 10;
68 static const double eps = 1e-8;
69 
70 void displayImage(cv::Mat &image)
71 {
72  for (int i=0; i<image.rows; i++)
73  {
74  for (int j=0; j<image.cols; j++)
75  {
76  printf("%3u ", image.at<unsigned char>(i, j));
77  }
78  printf("\n");
79  }
80 }
81 
83 {
84  CvLaserBridge bridge;
85 
86  calibration_msgs::DenseLaserSnapshot snapshot;
87 
88  snapshot = buildSnapshot(100.0, 0.0, 1.0, NUM_SCANS, RAYS_PER_SCAN);
89 
90  bool result;
91 
92  result = bridge.fromIntensity(snapshot, 0, 49);
93  cv::Mat image = bridge.toCvMat();
94 
95  ASSERT_TRUE(result);
96  ASSERT_TRUE(image.data);
97 
98  EXPECT_EQ(image.rows, (int) NUM_SCANS);
99  EXPECT_EQ(image.cols, (int) RAYS_PER_SCAN);
100 
101  if (DEBUG)
102  displayImage(image);
103 
104  // Check the first and last pixel in the image
105  EXPECT_EQ( (int) *((unsigned char*)(image.data)+0), 0);
106  EXPECT_EQ( (int) *((unsigned char*)(image.data)+4*image.step + 9), 255);
107 }
108 
109 TEST(CvLaserBridge, saturationTest)
110 {
111  CvLaserBridge bridge;
112  calibration_msgs::DenseLaserSnapshot snapshot;
113  snapshot = buildSnapshot(100.0, 0.0, 1.0, NUM_SCANS, RAYS_PER_SCAN);
114 
115  bool result;
116  result = bridge.fromIntensity(snapshot, 10, 20);
117  cv::Mat image = bridge.toCvMat();
118  ASSERT_TRUE(result);
119  ASSERT_TRUE(image.data);
120 
121  EXPECT_EQ(image.rows, (int) NUM_SCANS);
122  EXPECT_EQ(image.cols, (int) RAYS_PER_SCAN);
123 
124  if (DEBUG)
125  displayImage(image);
126 
127  // Check to make sure some of the pixels saturated near the beginning and end of the range
128  EXPECT_EQ( (int) *((unsigned char*)(image.data)+5), 0);
129  EXPECT_EQ( (int) *((unsigned char*)(image.data)+45), 255);
130 }
131 
132 
133 
134 int main(int argc, char **argv){
135  testing::InitGoogleTest(&argc, argv);
136  return RUN_ALL_TESTS();
137 }
void displayImage(cv::Mat &image)
static const bool DEBUG
bool fromIntensity(const calibration_msgs::DenseLaserSnapshot &snapshot, float min_val, float max_val)
static const double eps
static const unsigned int RAYS_PER_SCAN
TEST(CvLaserBridge, easy)
int main(int argc, char **argv)
static const unsigned int NUM_SCANS
calibration_msgs::DenseLaserSnapshot buildSnapshot(double start_range, double start_intensity, double increment, const unsigned int H, const unsigned int W)


laser_cb_detector
Author(s): Vijay Pradeep
autogenerated on Fri Apr 2 2021 02:13:03