Skip to content

Commit

Permalink
fix: modify some tests (#452)
Browse files Browse the repository at this point in the history
* Fixing new linter errors.

* Changing command for running tests.

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* remove relative file path

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* remove unnecessary main

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* fix: restore hdl64e s2 float intensities test

Signed-off-by: Daisuke Nishimatsu <border_goldenmarket@yahoo.co.jp>

Co-authored-by: Joshua Whitley <jwhitley@autonomoustuff.com>
  • Loading branch information
wep21 and Joshua Whitley committed Jul 18, 2022
1 parent 81fbc6e commit 37a2b71
Show file tree
Hide file tree
Showing 3 changed files with 32 additions and 33 deletions.
19 changes: 15 additions & 4 deletions velodyne_pointcloud/tests/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,10 +10,21 @@ 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
)

target_link_libraries(test_calibration
velodyne_rawdata
)

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
46 changes: 17 additions & 29 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 @@ -149,10 +148,7 @@ TEST(Calibration, hdl64e_s21)

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);
Calibration calibration(get_package_path() + "/params/issue_84_float_intensities.yaml");
ASSERT_EQ(calibration.num_lasers, 64);

// check some values for the first laser:
Expand All @@ -179,11 +175,3 @@ TEST(Calibration, hdl64e_s2_float_intensities)
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();
}

0 comments on commit 37a2b71

Please sign in to comment.