Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix: modify some tests #452

Merged
merged 4 commits into from
Jul 18, 2022
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 12 additions & 4 deletions velodyne_pointcloud/tests/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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
JWhitleyWork marked this conversation as resolved.
Show resolved Hide resolved
)

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.
Expand Down
67 changes: 16 additions & 51 deletions velodyne_pointcloud/tests/test_calibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,29 +32,35 @@

#include <gtest/gtest.h>

#include <ros/package.h>
#include <ament_index_cpp/get_package_share_directory.hpp>

#include <velodyne_pointcloud/calibration.hpp>

#include <string>

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:
Expand All @@ -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:
Expand All @@ -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:
Expand All @@ -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:
Expand All @@ -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);
}
JWhitleyWork marked this conversation as resolved.
Show resolved Hide resolved

// 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();
}
JWhitleyWork marked this conversation as resolved.
Show resolved Hide resolved