test_calibration.cpp
Go to the documentation of this file.
1 // Copyright (C) 2012, 2019 Austin Robot Technology, Jack O'Quin, Joshua Whitley
2 // All rights reserved.
3 //
4 // Software License Agreement (BSD License 2.0)
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions
8 // are met:
9 //
10 // * Redistributions of source code must retain the above copyright
11 // notice, this list of conditions and the following disclaimer.
12 // * Redistributions in binary form must reproduce the above
13 // copyright notice, this list of conditions and the following
14 // disclaimer in the documentation and/or other materials provided
15 // with the distribution.
16 // * Neither the name of {copyright_holder} nor the names of its
17 // contributors may be used to endorse or promote products derived
18 // from this software without specific prior written permission.
19 //
20 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 // POSSIBILITY OF SUCH DAMAGE.
32 
33 #include <gtest/gtest.h>
34 
35 #include <ros/package.h>
37 
38 #include <string>
39 
40 using namespace velodyne_pointcloud; // NOLINT
41 
42 std::string get_package_path()
43 {
44  std::string g_package_name("velodyne_pointcloud");
45  return ros::package::getPath(g_package_name);
46 }
47 
49 // Test cases
51 
52 TEST(Calibration, missing_file)
53 {
54  Calibration calibration(false);
55  calibration.read("./no_such_file.yaml");
56  EXPECT_FALSE(calibration.initialized);
57 }
58 
60 {
61  Calibration calibration(get_package_path() + "/params/VLP16db.yaml", false);
62  EXPECT_TRUE(calibration.initialized);
63  ASSERT_EQ(calibration.num_lasers, 16);
64 
65  // check some values for the first laser:
66  LaserCorrection laser = calibration.laser_corrections[0];
67  EXPECT_FALSE(laser.two_pt_correction_available);
68  EXPECT_FLOAT_EQ(laser.vert_correction, -0.2617993877991494);
69  EXPECT_FLOAT_EQ(laser.horiz_offset_correction, 0.0);
70  EXPECT_EQ(laser.max_intensity, 255);
71  EXPECT_EQ(laser.min_intensity, 0);
72 
73  // check similar values for the last laser:
74  laser = calibration.laser_corrections[15];
75  EXPECT_FALSE(laser.two_pt_correction_available);
76  EXPECT_FLOAT_EQ(laser.vert_correction, 0.2617993877991494);
77  EXPECT_FLOAT_EQ(laser.horiz_offset_correction, 0.0);
78  EXPECT_EQ(laser.max_intensity, 255);
79  EXPECT_EQ(laser.min_intensity, 0);
80 }
81 
82 TEST(Calibration, hdl32e)
83 {
84  Calibration calibration(get_package_path() + "/params/32db.yaml", false);
85  EXPECT_TRUE(calibration.initialized);
86  ASSERT_EQ(calibration.num_lasers, 32);
87 
88  // check some values for the first laser:
89  LaserCorrection laser = calibration.laser_corrections[0];
90  EXPECT_FALSE(laser.two_pt_correction_available);
91  EXPECT_FLOAT_EQ(laser.vert_correction, -0.5352924815866609);
92  EXPECT_FLOAT_EQ(laser.horiz_offset_correction, 0.0);
93  EXPECT_EQ(laser.max_intensity, 255);
94  EXPECT_EQ(laser.min_intensity, 0);
95 
96  // check similar values for the last laser:
97  laser = calibration.laser_corrections[31];
98  EXPECT_FALSE(laser.two_pt_correction_available);
99  EXPECT_FLOAT_EQ(laser.vert_correction, 0.18622663118779495);
100  EXPECT_FLOAT_EQ(laser.horiz_offset_correction, 0.0);
101  EXPECT_EQ(laser.max_intensity, 255);
102  EXPECT_EQ(laser.min_intensity, 0);
103 }
104 
106 {
107  Calibration calibration(get_package_path() + "/params/64e_utexas.yaml", false);
108  EXPECT_TRUE(calibration.initialized);
109  ASSERT_EQ(calibration.num_lasers, 64);
110 
111  // check some values for the first laser:
112  LaserCorrection laser = calibration.laser_corrections[0];
113  EXPECT_TRUE(laser.two_pt_correction_available);
114  EXPECT_FLOAT_EQ(laser.vert_correction, -0.124932751059532);
115  EXPECT_FLOAT_EQ(laser.horiz_offset_correction, 0.0);
116  EXPECT_EQ(laser.max_intensity, 255);
117  EXPECT_EQ(laser.min_intensity, 0);
118 
119  // check similar values for the last laser:
120  laser = calibration.laser_corrections[63];
121  EXPECT_TRUE(laser.two_pt_correction_available);
122  EXPECT_FLOAT_EQ(laser.vert_correction, -0.209881335496902);
123  EXPECT_FLOAT_EQ(laser.horiz_offset_correction, 0.0);
124  EXPECT_EQ(laser.max_intensity, 255);
125  EXPECT_EQ(laser.min_intensity, 0);
126 }
127 
128 TEST(Calibration, hdl64e_s21)
129 {
130  Calibration calibration(get_package_path() + "/params/64e_s2.1-sztaki.yaml",
131  false);
132  EXPECT_TRUE(calibration.initialized);
133  ASSERT_EQ(calibration.num_lasers, 64);
134 
135  // check some values for the first laser:
136  LaserCorrection laser = calibration.laser_corrections[0];
137  EXPECT_TRUE(laser.two_pt_correction_available);
138  EXPECT_FLOAT_EQ(laser.vert_correction, -0.15304134919741974);
139  EXPECT_FLOAT_EQ(laser.horiz_offset_correction, 0.025999999);
140  EXPECT_EQ(laser.max_intensity, 235);
141  EXPECT_EQ(laser.min_intensity, 30);
142 
143  // check similar values for the last laser:
144  laser = calibration.laser_corrections[63];
145  EXPECT_TRUE(laser.two_pt_correction_available);
146  EXPECT_FLOAT_EQ(laser.vert_correction, -0.2106649408137298);
147  EXPECT_FLOAT_EQ(laser.horiz_offset_correction, -0.025999999);
148  EXPECT_EQ(laser.max_intensity, 255);
149  EXPECT_EQ(laser.min_intensity, 0);
150 }
151 
152 TEST(Calibration, hdl64e_s2_float_intensities)
153 {
155  "/tests/issue_84_float_intensities.yaml",
156  false);
157  EXPECT_TRUE(calibration.initialized);
158  ASSERT_EQ(calibration.num_lasers, 64);
159 
160  // check some values for the first laser:
161  LaserCorrection laser = calibration.laser_corrections[0];
162  EXPECT_FALSE(laser.two_pt_correction_available);
163  EXPECT_FLOAT_EQ(laser.vert_correction, -0.12118950050089745);
164  EXPECT_FLOAT_EQ(laser.horiz_offset_correction, 0.025999999);
165  EXPECT_EQ(laser.max_intensity, 255);
166  EXPECT_EQ(laser.min_intensity, 40);
167 
168  // check similar values for laser 26:
169  laser = calibration.laser_corrections[26];
170  EXPECT_FALSE(laser.two_pt_correction_available);
171  EXPECT_FLOAT_EQ(laser.vert_correction, -0.014916840599137901);
172  EXPECT_FLOAT_EQ(laser.horiz_offset_correction, 0.025999999);
173  EXPECT_EQ(laser.max_intensity, 245);
174  EXPECT_EQ(laser.min_intensity, 0);
175 
176  // check similar values for the last laser:
177  laser = calibration.laser_corrections[63];
178  EXPECT_FALSE(laser.two_pt_correction_available);
179  EXPECT_FLOAT_EQ(laser.vert_correction, -0.20683046990039078);
180  EXPECT_FLOAT_EQ(laser.horiz_offset_correction, -0.025999999);
181  EXPECT_EQ(laser.max_intensity, 255);
182  EXPECT_EQ(laser.min_intensity, 0);
183 }
184 
185 // Run all the tests that were declared with TEST()
186 int main(int argc, char **argv)
187 {
188  testing::InitGoogleTest(&argc, argv);
189  return RUN_ALL_TESTS();
190 }
191 
velodyne_pointcloud
Definition: calibration.h:40
ros::package::getPath
ROSLIB_DECL std::string getPath(const std::string &package_name)
main
int main(int argc, char **argv)
Definition: test_calibration.cpp:186
add_two_pt.calibration
calibration
Definition: add_two_pt.py:14
velodyne_pointcloud::Calibration
Calibration information for the entire device.
Definition: calibration.h:78
velodyne_pointcloud::LaserCorrection
correction values for a single laser
Definition: calibration.h:52
velodyne_pointcloud::LaserCorrection::min_intensity
int min_intensity
Definition: calibration.h:64
package.h
TEST
TEST(Calibration, missing_file)
Definition: test_calibration.cpp:52
velodyne_pointcloud::LaserCorrection::vert_correction
float vert_correction
Definition: calibration.h:56
get_package_path
std::string get_package_path()
Definition: test_calibration.cpp:42
velodyne_pointcloud::LaserCorrection::two_pt_correction_available
bool two_pt_correction_available
Definition: calibration.h:58
calibration.h
velodyne_pointcloud::LaserCorrection::horiz_offset_correction
float horiz_offset_correction
Definition: calibration.h:62
velodyne_pointcloud::LaserCorrection::max_intensity
int max_intensity
Definition: calibration.h:63


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Fri Aug 2 2024 08:46:25