Skip to content

Commit

Permalink
add test for vlp32 that passes with current driver (#141)
Browse files Browse the repository at this point in the history
Co-authored-by: Max Schmeller <[email protected]>
  • Loading branch information
bgilby59 and mojomex authored Apr 24, 2024
1 parent 8fe029e commit affb619
Show file tree
Hide file tree
Showing 7 changed files with 557 additions and 0 deletions.
Binary file not shown.
Binary file not shown.
26 changes: 26 additions & 0 deletions nebula_tests/data/velodyne/vlp32/1713492677464078412/metadata.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
rosbag2_bagfile_information:
version: 5
storage_identifier: sqlite3
duration:
nanoseconds: 376987098
starting_time:
nanoseconds_since_epoch: 1713492677464078412
message_count: 5
topics_with_message_count:
- topic_metadata:
name: /sensing/lidar/front/velodyne_packets
type: velodyne_msgs/msg/VelodyneScan
serialization_format: cdr
offered_qos_profiles: ""
message_count: 5
compression_format: ""
compression_mode: ""
relative_file_paths:
- 1713492677464078412_0.db3
files:
- path: 1713492677464078412_0.db3
starting_time:
nanoseconds_since_epoch: 1713492677464078412
duration:
nanoseconds: 376987098
message_count: 5
21 changes: 21 additions & 0 deletions nebula_tests/velodyne/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -39,3 +39,24 @@ target_link_libraries(velodyne_ros_decoder_test_main_vls128
${PCL_LIBRARIES}
velodyne_ros_decoder_test_vls128
)

# Velodyne VLP32
ament_auto_add_library(velodyne_ros_decoder_test_vlp32 SHARED
velodyne_ros_decoder_test_vlp32.cpp
)
target_link_libraries(velodyne_ros_decoder_test_vlp32 ${PCL_LIBRARIES} ${NEBULA_TEST_LIBRARIES})

ament_add_gtest(velodyne_ros_decoder_test_main_vlp32
velodyne_ros_decoder_test_main_vlp32.cpp
)
ament_target_dependencies(velodyne_ros_decoder_test_main_vlp32
${NEBULA_TEST_DEPENDENCIES}
)
target_include_directories(velodyne_ros_decoder_test_main_vlp32 PUBLIC
${PROJECT_SOURCE_DIR}/src/velodyne
include
)
target_link_libraries(velodyne_ros_decoder_test_main_vlp32
${PCL_LIBRARIES}
velodyne_ros_decoder_test_vlp32
)
46 changes: 46 additions & 0 deletions nebula_tests/velodyne/velodyne_ros_decoder_test_main_vlp32.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
#include "velodyne_ros_decoder_test_vlp32.hpp"

#include <rclcpp/rclcpp.hpp>

#include <gtest/gtest.h>

#include <memory>

std::shared_ptr<nebula::ros::VelodyneRosDecoderTest> velodyne_driver;

TEST(TestDecoder, TestPcd)
{
std::cout << "TEST(TestDecoder, TestPcd)" << std::endl;
velodyne_driver->ReadBag();
}

int main(int argc, char * argv[])
{
std::cout << "velodyne_ros_decoder_test_main_vlp32.cpp" << std::endl;
setvbuf(stdout, NULL, _IONBF, BUFSIZ);

std::string node_name = "nebula_velodyne_decoder_test";

rclcpp::init(argc, argv);
::testing::InitGoogleTest(&argc, argv);
rclcpp::executors::SingleThreadedExecutor exec;
rclcpp::NodeOptions options;

velodyne_driver = std::make_shared<nebula::ros::VelodyneRosDecoderTest>(options, node_name);
exec.add_node(velodyne_driver->get_node_base_interface());

RCLCPP_INFO_STREAM(rclcpp::get_logger(node_name), "Get Status");
nebula::Status driver_status = velodyne_driver->GetStatus();
int result = 0;
if (driver_status == nebula::Status::OK) {
RCLCPP_INFO_STREAM(rclcpp::get_logger(node_name), "Reading Started");
result = RUN_ALL_TESTS();
} else {
RCLCPP_ERROR_STREAM(rclcpp::get_logger(node_name), driver_status);
}
RCLCPP_INFO_STREAM(rclcpp::get_logger(node_name), "Ending");
velodyne_driver.reset();
rclcpp::shutdown();

return result;
}
Loading

0 comments on commit affb619

Please sign in to comment.