test_calibration.cpp
Go to the documentation of this file.
00001 // Copyright (C) 2012, 2019 Austin Robot Technology, Jack O'Quin, Joshua Whitley
00002 // All rights reserved.
00003 //
00004 // Software License Agreement (BSD License 2.0)
00005 //
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions
00008 // are met:
00009 //
00010 //  * Redistributions of source code must retain the above copyright
00011 //    notice, this list of conditions and the following disclaimer.
00012 //  * Redistributions in binary form must reproduce the above
00013 //    copyright notice, this list of conditions and the following
00014 //    disclaimer in the documentation and/or other materials provided
00015 //    with the distribution.
00016 //  * Neither the name of {copyright_holder} nor the names of its
00017 //    contributors may be used to endorse or promote products derived
00018 //    from this software without specific prior written permission.
00019 //
00020 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 // POSSIBILITY OF SUCH DAMAGE.
00032 
00033 #include <gtest/gtest.h>
00034 
00035 #include <ros/package.h>
00036 #include <velodyne_pointcloud/calibration.h>
00037 
00038 #include <string>
00039 
00040 using namespace velodyne_pointcloud;  // NOLINT
00041 
00042 // global test data
00043 std::string g_package_name("velodyne_pointcloud");
00044 std::string g_package_path;
00045 
00046 void init_global_data(void)
00047 {
00048   g_package_path = ros::package::getPath(g_package_name);
00049 }
00050 
00052 // Test cases
00054 
00055 TEST(Calibration, missing_file)
00056 {
00057   Calibration calibration(false);
00058   calibration.read("./no_such_file.yaml");
00059   EXPECT_FALSE(calibration.initialized);
00060 }
00061 
00062 TEST(Calibration, vlp16)
00063 {
00064   Calibration calibration(g_package_path + "/params/VLP16db.yaml", false);
00065   EXPECT_TRUE(calibration.initialized);
00066   ASSERT_EQ(calibration.num_lasers, 16);
00067 
00068   // check some values for the first laser:
00069   LaserCorrection laser = calibration.laser_corrections[0];
00070   EXPECT_FALSE(laser.two_pt_correction_available);
00071   EXPECT_FLOAT_EQ(laser.vert_correction, -0.2617993877991494);
00072   EXPECT_FLOAT_EQ(laser.horiz_offset_correction, 0.0);
00073   EXPECT_EQ(laser.max_intensity, 255);
00074   EXPECT_EQ(laser.min_intensity, 0);
00075 
00076   // check similar values for the last laser:
00077   laser = calibration.laser_corrections[15];
00078   EXPECT_FALSE(laser.two_pt_correction_available);
00079   EXPECT_FLOAT_EQ(laser.vert_correction, 0.2617993877991494);
00080   EXPECT_FLOAT_EQ(laser.horiz_offset_correction, 0.0);
00081   EXPECT_EQ(laser.max_intensity, 255);
00082   EXPECT_EQ(laser.min_intensity, 0);
00083 }
00084 
00085 TEST(Calibration, hdl32e)
00086 {
00087   Calibration calibration(g_package_path + "/params/32db.yaml", false);
00088   EXPECT_TRUE(calibration.initialized);
00089   ASSERT_EQ(calibration.num_lasers, 32);
00090 
00091   // check some values for the first laser:
00092   LaserCorrection laser = calibration.laser_corrections[0];
00093   EXPECT_FALSE(laser.two_pt_correction_available);
00094   EXPECT_FLOAT_EQ(laser.vert_correction, -0.5352924815866609);
00095   EXPECT_FLOAT_EQ(laser.horiz_offset_correction, 0.0);
00096   EXPECT_EQ(laser.max_intensity, 255);
00097   EXPECT_EQ(laser.min_intensity, 0);
00098 
00099   // check similar values for the last laser:
00100   laser = calibration.laser_corrections[31];
00101   EXPECT_FALSE(laser.two_pt_correction_available);
00102   EXPECT_FLOAT_EQ(laser.vert_correction, 0.18622663118779495);
00103   EXPECT_FLOAT_EQ(laser.horiz_offset_correction, 0.0);
00104   EXPECT_EQ(laser.max_intensity, 255);
00105   EXPECT_EQ(laser.min_intensity, 0);
00106 }
00107 
00108 TEST(Calibration, hdl64e)
00109 {
00110   Calibration calibration(g_package_path + "/params/64e_utexas.yaml", false);
00111   EXPECT_TRUE(calibration.initialized);
00112   ASSERT_EQ(calibration.num_lasers, 64);
00113 
00114   // check some values for the first laser:
00115   LaserCorrection laser = calibration.laser_corrections[0];
00116   EXPECT_FALSE(laser.two_pt_correction_available);
00117   EXPECT_FLOAT_EQ(laser.vert_correction, -0.124932751059532);
00118   EXPECT_FLOAT_EQ(laser.horiz_offset_correction, 0.0);
00119   EXPECT_EQ(laser.max_intensity, 255);
00120   EXPECT_EQ(laser.min_intensity, 0);
00121 
00122   // check similar values for the last laser:
00123   laser = calibration.laser_corrections[63];
00124   EXPECT_FALSE(laser.two_pt_correction_available);
00125   EXPECT_FLOAT_EQ(laser.vert_correction, -0.209881335496902);
00126   EXPECT_FLOAT_EQ(laser.horiz_offset_correction, 0.0);
00127   EXPECT_EQ(laser.max_intensity, 255);
00128   EXPECT_EQ(laser.min_intensity, 0);
00129 }
00130 
00131 TEST(Calibration, hdl64e_s21)
00132 {
00133   Calibration calibration(g_package_path + "/params/64e_s2.1-sztaki.yaml",
00134                           false);
00135   EXPECT_TRUE(calibration.initialized);
00136   ASSERT_EQ(calibration.num_lasers, 64);
00137 
00138   // check some values for the first laser:
00139   LaserCorrection laser = calibration.laser_corrections[0];
00140   EXPECT_FALSE(laser.two_pt_correction_available);
00141   EXPECT_FLOAT_EQ(laser.vert_correction, -0.15304134919741974);
00142   EXPECT_FLOAT_EQ(laser.horiz_offset_correction, 0.025999999);
00143   EXPECT_EQ(laser.max_intensity, 235);
00144   EXPECT_EQ(laser.min_intensity, 30);
00145 
00146   // check similar values for the last laser:
00147   laser = calibration.laser_corrections[63];
00148   EXPECT_FALSE(laser.two_pt_correction_available);
00149   EXPECT_FLOAT_EQ(laser.vert_correction, -0.2106649408137298);
00150   EXPECT_FLOAT_EQ(laser.horiz_offset_correction, -0.025999999);
00151   EXPECT_EQ(laser.max_intensity, 255);
00152   EXPECT_EQ(laser.min_intensity, 0);
00153 }
00154 
00155 TEST(Calibration, hdl64e_s2_float_intensities)
00156 {
00157   Calibration calibration(g_package_path +
00158                           "/tests/issue_84_float_intensities.yaml",
00159                           false);
00160   EXPECT_TRUE(calibration.initialized);
00161   ASSERT_EQ(calibration.num_lasers, 64);
00162 
00163   // check some values for the first laser:
00164   LaserCorrection laser = calibration.laser_corrections[0];
00165   EXPECT_FALSE(laser.two_pt_correction_available);
00166   EXPECT_FLOAT_EQ(laser.vert_correction, -0.12118950050089745);
00167   EXPECT_FLOAT_EQ(laser.horiz_offset_correction, 0.025999999);
00168   EXPECT_EQ(laser.max_intensity, 255);
00169   EXPECT_EQ(laser.min_intensity, 40);
00170 
00171   // check similar values for laser 26:
00172   laser = calibration.laser_corrections[26];
00173   EXPECT_FALSE(laser.two_pt_correction_available);
00174   EXPECT_FLOAT_EQ(laser.vert_correction, -0.014916840599137901);
00175   EXPECT_FLOAT_EQ(laser.horiz_offset_correction, 0.025999999);
00176   EXPECT_EQ(laser.max_intensity, 245);
00177   EXPECT_EQ(laser.min_intensity, 0);
00178 
00179   // check similar values for the last laser:
00180   laser = calibration.laser_corrections[63];
00181   EXPECT_FALSE(laser.two_pt_correction_available);
00182   EXPECT_FLOAT_EQ(laser.vert_correction, -0.20683046990039078);
00183   EXPECT_FLOAT_EQ(laser.horiz_offset_correction, -0.025999999);
00184   EXPECT_EQ(laser.max_intensity, 255);
00185   EXPECT_EQ(laser.min_intensity, 0);
00186 }
00187 
00188 // Run all the tests that were declared with TEST()
00189 int main(int argc, char **argv)
00190 {
00191   testing::InitGoogleTest(&argc, argv);
00192   init_global_data();
00193   return RUN_ALL_TESTS();
00194 }
00195 


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Wed Jul 3 2019 19:32:23