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

feat: hesai timezone unit tests #81

Merged
merged 6 commits into from
Oct 17, 2023
Merged
Show file tree
Hide file tree
Changes from 5 commits
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
5 changes: 3 additions & 2 deletions .cspell.json
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
"gprmc",
"Hesai",
"memcpy",
"mkdoxy",
"nohup",
"nproc",
"pandar",
Expand All @@ -19,6 +20,7 @@
"PANDARXT",
"Pdelay",
"QT",
"rclcpp",
"schedutil",
"STD_COUT",
"stds",
Expand All @@ -28,7 +30,6 @@
"vccint",
"Vccint",
"XT",
"XTM",
"mkdoxy"
"XTM"
]
}
142 changes: 9 additions & 133 deletions nebula_tests/hesai/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,146 +1,22 @@
# Pandar AT128
ament_auto_add_library(hesai_ros_decoder_test_at128 SHARED
hesai_ros_decoder_test_at128.cpp
ament_auto_add_library(hesai_ros_decoder_test SHARED
hesai_ros_decoder_test.cpp
)
target_link_libraries(hesai_ros_decoder_test_at128 ${PCL_LIBRARIES} ${NEBULA_TEST_LIBRARIES})
target_link_libraries(hesai_ros_decoder_test ${PCL_LIBRARIES} ${NEBULA_TEST_LIBRARIES})

ament_add_gtest(hesai_ros_decoder_test_main_at128
hesai_ros_decoder_test_main_at128.cpp
ament_add_gtest(hesai_ros_decoder_test_main
hesai_ros_decoder_test_main.cpp
)

ament_target_dependencies(hesai_ros_decoder_test_main_at128
ament_target_dependencies(hesai_ros_decoder_test_main
${NEBULA_TEST_DEPENDENCIES}
)

target_include_directories(hesai_ros_decoder_test_main_at128 PUBLIC
target_include_directories(hesai_ros_decoder_test_main PUBLIC
${PROJECT_SOURCE_DIR}/src/hesai
include
)

target_link_libraries(hesai_ros_decoder_test_main_at128
target_link_libraries(hesai_ros_decoder_test_main
${PCL_LIBRARIES}
hesai_ros_decoder_test_at128
)

# Pandar XT32M
ament_auto_add_library(hesai_ros_decoder_test_xt32m SHARED
hesai_ros_decoder_test_xt32m.cpp
)
target_link_libraries(hesai_ros_decoder_test_xt32m ${PCL_LIBRARIES} ${NEBULA_TEST_LIBRARIES})

ament_add_gtest(hesai_ros_decoder_test_main_xt32m
hesai_ros_decoder_test_main_xt32m.cpp
)

ament_target_dependencies(hesai_ros_decoder_test_main_xt32m
${NEBULA_TEST_DEPENDENCIES}
)

target_include_directories(hesai_ros_decoder_test_main_xt32m PUBLIC
${PROJECT_SOURCE_DIR}/src/hesai
include
)

target_link_libraries(hesai_ros_decoder_test_main_xt32m
${PCL_LIBRARIES}
hesai_ros_decoder_test_xt32m
)

# Pandar 40P
ament_auto_add_library(hesai_ros_decoder_test_40p SHARED
hesai_ros_decoder_test_40p.cpp
)

target_link_libraries(hesai_ros_decoder_test_40p ${PCL_LIBRARIES} ${NEBULA_TEST_LIBRARIES})

ament_add_gtest(hesai_ros_decoder_test_main_40p
hesai_ros_decoder_test_main_40p.cpp
)

ament_target_dependencies(hesai_ros_decoder_test_main_40p
${NEBULA_TEST_DEPENDENCIES}
)

target_include_directories(hesai_ros_decoder_test_main_40p PUBLIC
${PROJECT_SOURCE_DIR}/src/hesai
include
)

target_link_libraries(hesai_ros_decoder_test_main_40p
${PCL_LIBRARIES}
hesai_ros_decoder_test_40p
)

# Pandar 64
ament_auto_add_library(hesai_ros_decoder_test_64 SHARED
hesai_ros_decoder_test_64.cpp
)

target_link_libraries(hesai_ros_decoder_test_64 ${PCL_LIBRARIES} ${NEBULA_TEST_LIBRARIES})

ament_add_gtest(hesai_ros_decoder_test_main_64
hesai_ros_decoder_test_main_64.cpp
)

ament_target_dependencies(hesai_ros_decoder_test_main_64
${NEBULA_TEST_DEPENDENCIES}
)

target_include_directories(hesai_ros_decoder_test_main_64 PUBLIC
${PROJECT_SOURCE_DIR}/src/hesai
include
)

target_link_libraries(hesai_ros_decoder_test_main_64
${PCL_LIBRARIES}
hesai_ros_decoder_test_64
)

# Pandar QT64
ament_auto_add_library(hesai_ros_decoder_test_qt64 SHARED
hesai_ros_decoder_test_qt64.cpp
)

target_link_libraries(hesai_ros_decoder_test_qt64 ${PCL_LIBRARIES} ${NEBULA_TEST_LIBRARIES})

ament_add_gtest(hesai_ros_decoder_test_main_qt64
hesai_ros_decoder_test_main_qt64.cpp
)

ament_target_dependencies(hesai_ros_decoder_test_main_qt64
${NEBULA_TEST_DEPENDENCIES}
)
target_include_directories(hesai_ros_decoder_test_main_qt64 PUBLIC
${PROJECT_SOURCE_DIR}/src/hesai
include
)

target_link_libraries(hesai_ros_decoder_test_main_qt64
${PCL_LIBRARIES}
hesai_ros_decoder_test_qt64
)

# Pandar XT32
ament_auto_add_library(hesai_ros_decoder_test_xt32 SHARED
hesai_ros_decoder_test_xt32.cpp
)

target_link_libraries(hesai_ros_decoder_test_xt32 ${PCL_LIBRARIES} ${NEBULA_TEST_LIBRARIES})

ament_add_gtest(hesai_ros_decoder_test_main_xt32
hesai_ros_decoder_test_main_xt32.cpp
)

ament_target_dependencies(hesai_ros_decoder_test_main_xt32
${NEBULA_TEST_DEPENDENCIES}
)

target_include_directories(hesai_ros_decoder_test_main_xt32 PUBLIC
${PROJECT_SOURCE_DIR}/src/hesai
include
)

target_link_libraries(hesai_ros_decoder_test_main_xt32
${PCL_LIBRARIES}
hesai_ros_decoder_test_xt32
hesai_ros_decoder_test
)
32 changes: 31 additions & 1 deletion nebula_tests/hesai/hesai_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
#include "nebula_common/hesai/hesai_common.hpp"
#include "nebula_common/nebula_common.hpp"
#include "nebula_common/nebula_status.hpp"
#include "nebula_decoders/nebula_decoders_hesai/decoders/hesai_scan_decoder.hpp"
#include "nebula_decoders/nebula_decoders_hesai/hesai_driver.hpp"
#include "nebula_ros/common/nebula_driver_ros_wrapper_base.hpp"

Expand All @@ -14,10 +15,13 @@
#include "pandar_msgs/msg/pandar_scan.hpp"

#include <gtest/gtest.h>
#include <time.h>

#include <algorithm>

namespace nebula
{
namespace ros
namespace test
{

void checkPCDs(nebula::drivers::NebulaPointCloudPtr pc, pcl::PointCloud<pcl::PointXYZ>::Ptr pc_ref)
Expand All @@ -39,5 +43,31 @@ void checkPCDs(nebula::drivers::NebulaPointCloudPtr pc, pcl::PointCloud<pcl::Poi
}
}

void checkPCDs(nebula::drivers::NebulaPointCloudPtr pp1, nebula::drivers::NebulaPointCloudPtr pp2)
{
EXPECT_EQ(pp1->points.size(), pp2->points.size());
for (uint32_t i = 0; i < pp1->points.size(); i++) {
auto p1 = pp1->points[i];
auto p2 = pp2->points[i];
EXPECT_FLOAT_EQ(p1.x, p2.x);
EXPECT_FLOAT_EQ(p1.y, p2.y);
EXPECT_FLOAT_EQ(p1.z, p2.z);
EXPECT_FLOAT_EQ(p1.intensity, p2.intensity);
EXPECT_EQ(p1.channel, p2.channel);
EXPECT_FLOAT_EQ(p1.azimuth, p2.azimuth);
EXPECT_EQ(p1.return_type, p2.return_type);
EXPECT_DOUBLE_EQ(p1.time_stamp, p2.time_stamp);
}
}

void printPCD(nebula::drivers::NebulaPointCloudPtr pp)
{
for (auto p : pp->points) {
std::cout << "(" << p.x << ", " << p.y << "," << p.z << "): " << p.intensity << ", "
<< p.channel << ", " << p.azimuth << ", " << p.return_type << ", " << p.time_stamp
<< std::endl;
}
}

} // namespace ros
} // namespace nebula
Loading