diff --git a/velodyne_pointcloud/tests/CMakeLists.txt b/velodyne_pointcloud/tests/CMakeLists.txt index 624d46dd5..a1508d387 100644 --- a/velodyne_pointcloud/tests/CMakeLists.txt +++ b/velodyne_pointcloud/tests/CMakeLists.txt @@ -10,10 +10,18 @@ ament_target_dependencies(test_row_step velodyne_msgs ) -# C++ gtests -# catkin_add_gtest(test_calibration test_calibration.cpp) -# add_dependencies(test_calibration ${catkin_EXPORTED_TARGETS}) -# target_link_libraries(test_calibration velodyne_rawdata ${catkin_LIBRARIES}) +ament_add_gtest(test_calibration + test_calibration.cpp + ../src/lib/calibration.cpp +) + +ament_target_dependencies(test_calibration + rclcpp +) + +target_link_libraries(test_calibration + ${YAML_CPP_LIBRARIES} +) # # Download packet capture (PCAP) files containing test data. # # Store them in devel-space, so rostest can easily find them. diff --git a/velodyne_pointcloud/tests/test_calibration.cpp b/velodyne_pointcloud/tests/test_calibration.cpp index 406219dc9..e6116cbba 100644 --- a/velodyne_pointcloud/tests/test_calibration.cpp +++ b/velodyne_pointcloud/tests/test_calibration.cpp @@ -32,29 +32,35 @@ #include -#include +#include + #include #include using namespace velodyne_pointcloud; // NOLINT +std::string get_package_path() +{ + std::string g_package_name("velodyne_pointcloud"); + return ament_index_cpp::get_package_share_directory(g_package_name); +} + /////////////////////////////////////////////////////////////// // Test cases /////////////////////////////////////////////////////////////// TEST(Calibration, missing_file) { - Calibration calibration(false); - calibration.read("./no_such_file.yaml"); - EXPECT_FALSE(calibration.initialized); + EXPECT_THROW( + {Calibration calibration("/no_such_file.yaml");}, + std::runtime_error + ); } TEST(Calibration, vlp16) { - std::string g_package_path = ros::package::getPath("velodyne_pointcloud"); - Calibration calibration(g_package_path + "/params/VLP16db.yaml", false); - EXPECT_TRUE(calibration.initialized); + Calibration calibration(get_package_path() + "/params/VLP16db.yaml"); ASSERT_EQ(calibration.num_lasers, 16); // check some values for the first laser: @@ -76,9 +82,7 @@ TEST(Calibration, vlp16) TEST(Calibration, hdl32e) { - std::string g_package_path = ros::package::getPath("velodyne_pointcloud"); - Calibration calibration(g_package_path + "/params/32db.yaml", false); - EXPECT_TRUE(calibration.initialized); + Calibration calibration(get_package_path() + "/params/32db.yaml"); ASSERT_EQ(calibration.num_lasers, 32); // check some values for the first laser: @@ -100,9 +104,7 @@ TEST(Calibration, hdl32e) TEST(Calibration, hdl64e) { - std::string g_package_path = ros::package::getPath("velodyne_pointcloud"); - Calibration calibration(g_package_path + "/params/64e_utexas.yaml", false); - EXPECT_TRUE(calibration.initialized); + Calibration calibration(get_package_path() + "/params/64e_utexas.yaml"); ASSERT_EQ(calibration.num_lasers, 64); // check some values for the first laser: @@ -124,10 +126,7 @@ TEST(Calibration, hdl64e) TEST(Calibration, hdl64e_s21) { - std::string g_package_path = ros::package::getPath("velodyne_pointcloud"); - Calibration calibration( - g_package_path + "/params/64e_s2.1-sztaki.yaml", false); - EXPECT_TRUE(calibration.initialized); + Calibration calibration(get_package_path() + "/params/64e_s2.1-sztaki.yaml"); ASSERT_EQ(calibration.num_lasers, 64); // check some values for the first laser: @@ -147,43 +146,9 @@ TEST(Calibration, hdl64e_s21) EXPECT_EQ(laser.min_intensity, 0); } -TEST(Calibration, hdl64e_s2_float_intensities) -{ - std::string g_package_path = ros::package::getPath("velodyne_pointcloud"); - Calibration calibration( - g_package_path + "/tests/issue_84_float_intensities.yaml", false); - EXPECT_TRUE(calibration.initialized); - ASSERT_EQ(calibration.num_lasers, 64); - - // check some values for the first laser: - LaserCorrection laser = calibration.laser_corrections[0]; - EXPECT_FALSE(laser.two_pt_correction_available); - EXPECT_FLOAT_EQ(laser.vert_correction, -0.12118950050089745); - EXPECT_FLOAT_EQ(laser.horiz_offset_correction, 0.025999999); - EXPECT_EQ(laser.max_intensity, 255); - EXPECT_EQ(laser.min_intensity, 40); - - // check similar values for laser 26: - laser = calibration.laser_corrections[26]; - EXPECT_FALSE(laser.two_pt_correction_available); - EXPECT_FLOAT_EQ(laser.vert_correction, -0.014916840599137901); - EXPECT_FLOAT_EQ(laser.horiz_offset_correction, 0.025999999); - EXPECT_EQ(laser.max_intensity, 245); - EXPECT_EQ(laser.min_intensity, 0); - - // check similar values for the last laser: - laser = calibration.laser_corrections[63]; - EXPECT_FALSE(laser.two_pt_correction_available); - EXPECT_FLOAT_EQ(laser.vert_correction, -0.20683046990039078); - EXPECT_FLOAT_EQ(laser.horiz_offset_correction, -0.025999999); - EXPECT_EQ(laser.max_intensity, 255); - EXPECT_EQ(laser.min_intensity, 0); -} - // Run all the tests that were declared with TEST() int main(int argc, char ** argv) { testing::InitGoogleTest(&argc, argv); - init_global_data(); return RUN_ALL_TESTS(); }