diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp index b96fac205..f6a5b5fb2 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp @@ -22,8 +22,8 @@ #include "nebula_common/velodyne/velodyne_calibration_decoder.hpp" #include "nebula_common/velodyne/velodyne_common.hpp" -#include "velodyne_msgs/msg/velodyne_packet.hpp" -#include "velodyne_msgs/msg/velodyne_scan.hpp" +#include +#include #include diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp16_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp16_decoder.hpp index 0cfe33aa5..ed8ef2e32 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp16_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp16_decoder.hpp @@ -2,8 +2,8 @@ #include "nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp" -#include "velodyne_msgs/msg/velodyne_packet.hpp" -#include "velodyne_msgs/msg/velodyne_scan.hpp" +#include +#include #include diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp32_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp32_decoder.hpp index 4fd5f4c03..28db49afa 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp32_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp32_decoder.hpp @@ -2,8 +2,8 @@ #include "nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp" -#include "velodyne_msgs/msg/velodyne_packet.hpp" -#include "velodyne_msgs/msg/velodyne_scan.hpp" +#include +#include #include diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vls128_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vls128_decoder.hpp index d0702371d..627b838a5 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vls128_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vls128_decoder.hpp @@ -2,8 +2,8 @@ #include "nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp" -#include "velodyne_msgs/msg/velodyne_packet.hpp" -#include "velodyne_msgs/msg/velodyne_scan.hpp" +#include +#include #include diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/velodyne_driver.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/velodyne_driver.hpp index d88b19db4..d0257b82d 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/velodyne_driver.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/velodyne_driver.hpp @@ -8,8 +8,8 @@ #include "nebula_decoders/nebula_decoders_common/nebula_driver_base.hpp" #include "nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp" -#include "velodyne_msgs/msg/velodyne_packet.hpp" -#include "velodyne_msgs/msg/velodyne_scan.hpp" +#include +#include #include diff --git a/nebula_examples/include/velodyne/velodyne_ros_offline_extract_bag_pcd.hpp b/nebula_examples/include/velodyne/velodyne_ros_offline_extract_bag_pcd.hpp index 7818a050d..c1910d294 100644 --- a/nebula_examples/include/velodyne/velodyne_ros_offline_extract_bag_pcd.hpp +++ b/nebula_examples/include/velodyne/velodyne_ros_offline_extract_bag_pcd.hpp @@ -35,8 +35,8 @@ #include #include -#include "velodyne_msgs/msg/velodyne_packet.hpp" -#include "velodyne_msgs/msg/velodyne_scan.hpp" +#include +#include #include diff --git a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp index a2bb8fc70..11126d69e 100644 --- a/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp +++ b/nebula_hw_interfaces/include/nebula_hw_interfaces/nebula_hw_interfaces_velodyne/velodyne_hw_interface.hpp @@ -19,8 +19,8 @@ #include -#include "velodyne_msgs/msg/velodyne_packet.hpp" -#include "velodyne_msgs/msg/velodyne_scan.hpp" +#include +#include #include #include diff --git a/nebula_messages/velodyne_msgs/CMakeLists.txt b/nebula_messages/velodyne_msgs/CMakeLists.txt deleted file mode 100644 index 42f375687..000000000 --- a/nebula_messages/velodyne_msgs/CMakeLists.txt +++ /dev/null @@ -1,24 +0,0 @@ -cmake_minimum_required(VERSION 3.5) -project(velodyne_msgs) - -if (NOT CMAKE_CXX_STANDARD) - set(CMAKE_CXX_STANDARD 14) - set(CMAKE_CXX_STANDARD_REQUIRED ON) - set(CMAKE_CXX_EXTENSIONS OFF) -endif () - -if (CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) -endif () - -find_package(ament_cmake_auto REQUIRED) -ament_auto_find_build_dependencies() - -rosidl_generate_interfaces(${PROJECT_NAME} - "msg/VelodynePacket.msg" - "msg/VelodyneScan.msg" - DEPENDENCIES - std_msgs - ) - -ament_package() diff --git a/nebula_messages/velodyne_msgs/msg/VelodynePacket.msg b/nebula_messages/velodyne_msgs/msg/VelodynePacket.msg deleted file mode 100644 index 87a8d3a44..000000000 --- a/nebula_messages/velodyne_msgs/msg/VelodynePacket.msg +++ /dev/null @@ -1,4 +0,0 @@ -# Raw Velodyne LIDAR packet. - -builtin_interfaces/Time stamp # packet timestamp -uint8[1206] data # packet contents diff --git a/nebula_messages/velodyne_msgs/msg/VelodyneScan.msg b/nebula_messages/velodyne_msgs/msg/VelodyneScan.msg deleted file mode 100644 index d4f3e06a9..000000000 --- a/nebula_messages/velodyne_msgs/msg/VelodyneScan.msg +++ /dev/null @@ -1,4 +0,0 @@ -# Velodyne LIDAR scan packets. - -std_msgs/Header header # standard ROS message header -VelodynePacket[] packets # vector of raw packets diff --git a/nebula_messages/velodyne_msgs/package.xml b/nebula_messages/velodyne_msgs/package.xml deleted file mode 100644 index 1b1268741..000000000 --- a/nebula_messages/velodyne_msgs/package.xml +++ /dev/null @@ -1,19 +0,0 @@ - - - velodyne_msgs - 1.3.12 - Nebula ROS message definitions for Velodyne VLS3D LIDARs. - Perception Engine - BSD - - ament_cmake_auto - rosidl_default_generators - - std_msgs - rosidl_default_runtime - rosidl_interface_packages - - - ament_cmake - - diff --git a/nebula_ros/include/nebula_ros/velodyne/velodyne_decoder_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/velodyne/velodyne_decoder_ros_wrapper.hpp index d9a76e14e..5bc79b6c8 100644 --- a/nebula_ros/include/nebula_ros/velodyne/velodyne_decoder_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/velodyne/velodyne_decoder_ros_wrapper.hpp @@ -12,8 +12,8 @@ #include #include -#include "velodyne_msgs/msg/velodyne_packet.hpp" -#include "velodyne_msgs/msg/velodyne_scan.hpp" +#include +#include namespace nebula { diff --git a/nebula_ros/include/nebula_ros/velodyne/velodyne_hw_interface_ros_wrapper.hpp b/nebula_ros/include/nebula_ros/velodyne/velodyne_hw_interface_ros_wrapper.hpp index a5001b62f..a3606c091 100644 --- a/nebula_ros/include/nebula_ros/velodyne/velodyne_hw_interface_ros_wrapper.hpp +++ b/nebula_ros/include/nebula_ros/velodyne/velodyne_hw_interface_ros_wrapper.hpp @@ -10,8 +10,8 @@ #include #include -#include "velodyne_msgs/msg/velodyne_packet.hpp" -#include "velodyne_msgs/msg/velodyne_scan.hpp" +#include +#include #include diff --git a/nebula_ros/package.xml b/nebula_ros/package.xml index 3a9f2ecca..92b082e8a 100644 --- a/nebula_ros/package.xml +++ b/nebula_ros/package.xml @@ -22,6 +22,7 @@ rclcpp rclcpp_components yaml-cpp + velodyne_msgs ament_cmake_gtest ament_lint_auto diff --git a/nebula_tests/hesai/hesai_ros_decoder_test.hpp b/nebula_tests/hesai/hesai_ros_decoder_test.hpp index a055e1b2f..b66c996f8 100644 --- a/nebula_tests/hesai/hesai_ros_decoder_test.hpp +++ b/nebula_tests/hesai/hesai_ros_decoder_test.hpp @@ -35,11 +35,11 @@ struct HesaiRosDecoderTestParams { std::string sensor_model; std::string return_mode; - std::string frame_id = "hesai"; - double scan_phase = 0.; std::string calibration_file = ""; - std::string correction_file = ""; std::string bag_path; + std::string correction_file = ""; + std::string frame_id = "hesai"; + double scan_phase = 0.; std::string storage_id = "sqlite3"; std::string format = "cdr"; std::string target_topic = "/pandar_packets"; diff --git a/nebula_tests/hesai/hesai_ros_decoder_test_main.cpp b/nebula_tests/hesai/hesai_ros_decoder_test_main.cpp index c8a487a46..feda648f0 100644 --- a/nebula_tests/hesai/hesai_ros_decoder_test_main.cpp +++ b/nebula_tests/hesai/hesai_ros_decoder_test_main.cpp @@ -19,41 +19,42 @@ namespace test { const nebula::ros::HesaiRosDecoderTestParams TEST_CONFIGS[6] = { - {.sensor_model = "Pandar40P", - .return_mode = "Dual", - .calibration_file = "Pandar40P.csv", - .bag_path = "40p/1673400149412331409"}, { - .sensor_model = "Pandar64", - .return_mode = "Dual", - .calibration_file = "Pandar64.csv", - .bag_path = "64/1673403880599376836", + "Pandar40P", + "Dual", + "Pandar40P.csv", + "40p/1673400149412331409", }, { - .sensor_model = "PandarAT128", - .return_mode = "Dual", - .scan_phase = 152, - .calibration_file = "PandarAT128.csv", - .correction_file = "PandarAT128.dat", - .bag_path = "at128/1679653308406038376", + "Pandar64", + "Dual", + "Pandar64.csv", + "64/1673403880599376836", }, { - .sensor_model = "PandarQT64", - .return_mode = "Dual", - .calibration_file = "PandarQT64.csv", - .bag_path = "qt64/1673401195788312575", + "PandarAT128", + "LastStrongest", + "PandarAT128.csv", + "at128/1679653308406038376", + "PandarAT128.dat", }, { - .sensor_model = "PandarXT32", - .return_mode = "Dual", - .calibration_file = "PandarXT32.csv", - .bag_path = "xt32/1673400677802009732", + "PandarQT64", + "Dual", + "PandarQT64.csv", + "qt64/1673401195788312575", }, { - .sensor_model = "PandarXT32M", - .return_mode = "LastStrongest", - .calibration_file = "PandarXT32M.csv", - .bag_path = "xt32m/1660893203042895158", + "PandarXT32", + "Dual", + "PandarXT32.csv", + "xt32/1673400677802009732", + }, + { + "PandarXT32M", + "LastStrongest", + "PandarXT32M.csv", + "xt32m/1660893203042895158", }}; // Compares geometrical output of decoder against pre-recorded reference pointcloud. @@ -67,7 +68,7 @@ TEST_P(DecoderTest, TestPcd) int check_cnt = 0; auto scan_callback = [&]( - uint64_t msg_timestamp, uint64_t scan_timestamp, + uint64_t msg_timestamp, uint64_t /*scan_timestamp*/, nebula::drivers::NebulaPointCloudPtr pointcloud) { if (!pointcloud) return; @@ -98,7 +99,7 @@ TEST_P(DecoderTest, TestTimezone) std::vector decoded_timestamps; auto scan_callback = [&]( - uint64_t msg_timestamp, uint64_t scan_timestamp, + uint64_t /*msg_timestamp*/, uint64_t scan_timestamp, nebula::drivers::NebulaPointCloudPtr pointcloud) { if (!pointcloud) return; decoded_timestamps.push_back(scan_timestamp); @@ -134,7 +135,7 @@ TEST_P(DecoderTest, TestTimezone) // then compare e.g. the last timestamp to verify that it is not affected // by timezone settings ASSERT_EQ(decoded_timestamps.size(), decoded_timestamps_cmp.size()); - ASSERT_GT(decoded_timestamps.size(), 0); + ASSERT_GT(decoded_timestamps.size(), 0U); EXPECT_EQ(decoded_timestamps.back(), decoded_timestamps_cmp.back()); } diff --git a/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp16.hpp b/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp16.hpp index 8895c1c68..2b889358e 100644 --- a/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp16.hpp +++ b/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp16.hpp @@ -11,8 +11,8 @@ #include #include -#include "velodyne_msgs/msg/velodyne_packet.hpp" -#include "velodyne_msgs/msg/velodyne_scan.hpp" +#include +#include #include diff --git a/nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.hpp b/nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.hpp index 52b4968c3..a2432838f 100644 --- a/nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.hpp +++ b/nebula_tests/velodyne/velodyne_ros_decoder_test_vls128.hpp @@ -11,8 +11,8 @@ #include #include -#include "velodyne_msgs/msg/velodyne_packet.hpp" -#include "velodyne_msgs/msg/velodyne_scan.hpp" +#include +#include #include