diff --git a/nebula_tests/data/velodyne/vlp32/1713492677464078412.pcd b/nebula_tests/data/velodyne/vlp32/1713492677464078412.pcd new file mode 100644 index 000000000..6ae2e557f Binary files /dev/null and b/nebula_tests/data/velodyne/vlp32/1713492677464078412.pcd differ diff --git a/nebula_tests/data/velodyne/vlp32/1713492677464078412/1713492677464078412_0.db3 b/nebula_tests/data/velodyne/vlp32/1713492677464078412/1713492677464078412_0.db3 new file mode 100644 index 000000000..fa3ce78ba Binary files /dev/null and b/nebula_tests/data/velodyne/vlp32/1713492677464078412/1713492677464078412_0.db3 differ diff --git a/nebula_tests/data/velodyne/vlp32/1713492677464078412/metadata.yaml b/nebula_tests/data/velodyne/vlp32/1713492677464078412/metadata.yaml new file mode 100644 index 000000000..536456380 --- /dev/null +++ b/nebula_tests/data/velodyne/vlp32/1713492677464078412/metadata.yaml @@ -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 \ No newline at end of file diff --git a/nebula_tests/velodyne/CMakeLists.txt b/nebula_tests/velodyne/CMakeLists.txt index cbb1400ed..f166997bd 100644 --- a/nebula_tests/velodyne/CMakeLists.txt +++ b/nebula_tests/velodyne/CMakeLists.txt @@ -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 +) \ No newline at end of file diff --git a/nebula_tests/velodyne/velodyne_ros_decoder_test_main_vlp32.cpp b/nebula_tests/velodyne/velodyne_ros_decoder_test_main_vlp32.cpp new file mode 100644 index 000000000..eda4969c6 --- /dev/null +++ b/nebula_tests/velodyne/velodyne_ros_decoder_test_main_vlp32.cpp @@ -0,0 +1,46 @@ +#include "velodyne_ros_decoder_test_vlp32.hpp" + +#include + +#include + +#include + +std::shared_ptr 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(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; +} diff --git a/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp32.cpp b/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp32.cpp new file mode 100644 index 000000000..c7623ca50 --- /dev/null +++ b/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp32.cpp @@ -0,0 +1,373 @@ +#include "velodyne_ros_decoder_test_vlp32.hpp" + +#include "rclcpp/serialization.hpp" +#include "rclcpp/serialized_message.hpp" +#include "rcpputils/filesystem_helper.hpp" +#include "rcutils/time.h" +#include "rosbag2_cpp/reader.hpp" +#include "rosbag2_cpp/readers/sequential_reader.hpp" +#include "rosbag2_cpp/writer.hpp" +#include "rosbag2_cpp/writers/sequential_writer.hpp" +#include "rosbag2_storage/storage_options.hpp" + +#include + +#include +#include + +namespace nebula +{ +namespace ros +{ +VelodyneRosDecoderTest::VelodyneRosDecoderTest( + const rclcpp::NodeOptions & options, const std::string & node_name) +: rclcpp::Node(node_name, options) +{ + drivers::VelodyneCalibrationConfiguration calibration_configuration; + drivers::VelodyneSensorConfiguration sensor_configuration; + + wrapper_status_ = GetParameters(sensor_configuration, calibration_configuration); + if (Status::OK != wrapper_status_) { + RCLCPP_ERROR_STREAM(this->get_logger(), this->get_name() << " Error:" << wrapper_status_); + return; + } + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Starting..."); + + calibration_cfg_ptr_ = + std::make_shared(calibration_configuration); + + sensor_cfg_ptr_ = std::make_shared(sensor_configuration); + + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << ". Driver "); + wrapper_status_ = InitializeDriver( + std::const_pointer_cast(sensor_cfg_ptr_), + std::static_pointer_cast(calibration_cfg_ptr_)); + + RCLCPP_INFO_STREAM(this->get_logger(), this->get_name() << "Wrapper=" << wrapper_status_); +} + +Status VelodyneRosDecoderTest::InitializeDriver( + std::shared_ptr sensor_configuration, + std::shared_ptr calibration_configuration) +{ + // driver should be initialized here with proper decoder + driver_ptr_ = std::make_shared( + std::static_pointer_cast(sensor_configuration), + std::static_pointer_cast(calibration_configuration)); + return driver_ptr_->GetStatus(); +} + +Status VelodyneRosDecoderTest::GetStatus() +{ + return wrapper_status_; +} + +Status VelodyneRosDecoderTest::GetParameters( + drivers::VelodyneSensorConfiguration & sensor_configuration, + drivers::VelodyneCalibrationConfiguration & calibration_configuration) +{ + std::filesystem::path calib_dir = + _SRC_CALIBRATION_DIR_PATH; // variable defined in CMakeLists.txt; + calib_dir /= "velodyne"; + std::filesystem::path bag_root_dir = + _SRC_RESOURCES_DIR_PATH; // variable defined in CMakeLists.txt; + bag_root_dir /= "velodyne"; + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("sensor_model", "VLP32"); + sensor_configuration.sensor_model = + nebula::drivers::SensorModelFromString(this->get_parameter("sensor_model").as_string()); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("return_mode", "SingleStrongest", descriptor); + sensor_configuration.return_mode = + nebula::drivers::ReturnModeFromString(this->get_parameter("return_mode").as_string()); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("frame_id", "velodyne_front", descriptor); + sensor_configuration.frame_id = this->get_parameter("frame_id").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 3; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = "Angle where scans begin (degrees, [0.,360.]"; + rcl_interfaces::msg::FloatingPointRange range; + range.set__from_value(0).set__to_value(360).set__step(0.01); + descriptor.floating_point_range = {range}; + this->declare_parameter("scan_phase", 180.0, descriptor); + sensor_configuration.scan_phase = this->get_parameter("scan_phase").as_double(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter( + "calibration_file", (calib_dir / "VLP32.yaml").string(), descriptor); + calibration_configuration.calibration_file = + this->get_parameter("calibration_file").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 3; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("min_range", 0.4, descriptor); + sensor_configuration.min_range = this->get_parameter("min_range").as_double(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 3; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("max_range", 50.0, descriptor); + sensor_configuration.max_range = this->get_parameter("max_range").as_double(); + } + double view_direction = sensor_configuration.scan_phase * M_PI / 180; + double view_width = 360 * M_PI / 180; + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 3; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("view_width", 180.0, descriptor); + view_width = this->get_parameter("view_width").as_double() * M_PI / 180; + } + + if (sensor_configuration.sensor_model != nebula::drivers::SensorModel::VELODYNE_HDL64) { + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 2; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + rcl_interfaces::msg::IntegerRange range; + range.set__from_value(0).set__to_value(359).set__step(1); + descriptor.integer_range = {range}; + this->declare_parameter("cloud_min_angle", 270, descriptor); + sensor_configuration.cloud_min_angle = this->get_parameter("cloud_min_angle").as_int(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 2; + descriptor.read_only = false; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + rcl_interfaces::msg::IntegerRange range; + range.set__from_value(0).set__to_value(359).set__step(1); + descriptor.integer_range = {range}; + this->declare_parameter("cloud_max_angle", 90, descriptor); + sensor_configuration.cloud_max_angle = this->get_parameter("cloud_max_angle").as_int(); + } + } else { + double min_angle = fmod(fmod(view_direction + view_width / 2, 2 * M_PI) + 2 * M_PI, 2 * M_PI); + double max_angle = fmod(fmod(view_direction - view_width / 2, 2 * M_PI) + 2 * M_PI, 2 * M_PI); + sensor_configuration.cloud_min_angle = 100 * (2 * M_PI - min_angle) * 180 / M_PI + 0.5; + sensor_configuration.cloud_max_angle = 100 * (2 * M_PI - max_angle) * 180 / M_PI + 0.5; + if (sensor_configuration.cloud_min_angle == sensor_configuration.cloud_max_angle) { + // avoid returning empty cloud if min_angle = max_angle + sensor_configuration.cloud_min_angle = 0; + sensor_configuration.cloud_max_angle = 36000; + } + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter( + "bag_path", (bag_root_dir / "vlp32" / "1713492677464078412").string(), descriptor); + bag_path = this->get_parameter("bag_path").as_string(); + std::cout << bag_path << std::endl; + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("storage_id", "sqlite3", descriptor); + storage_id = this->get_parameter("storage_id").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter("format", "cdr", descriptor); + format = this->get_parameter("format").as_string(); + } + { + rcl_interfaces::msg::ParameterDescriptor descriptor; + descriptor.type = 4; + descriptor.read_only = true; + descriptor.dynamic_typing = false; + descriptor.additional_constraints = ""; + this->declare_parameter( + "target_topic", "/sensing/lidar/front/velodyne_packets", descriptor); + target_topic = this->get_parameter("target_topic").as_string(); + } + + if (sensor_configuration.sensor_model == nebula::drivers::SensorModel::UNKNOWN) { + return Status::INVALID_SENSOR_MODEL; + } + if (sensor_configuration.return_mode == nebula::drivers::ReturnMode::UNKNOWN) { + return Status::INVALID_ECHO_MODE; + } + if (sensor_configuration.frame_id.empty() || sensor_configuration.scan_phase > 360) { + return Status::SENSOR_CONFIG_ERROR; + } + if (calibration_configuration.calibration_file.empty()) { + return Status::INVALID_CALIBRATION_FILE; + } else { + auto cal_status = + calibration_configuration.LoadFromFile(calibration_configuration.calibration_file); + if (cal_status != Status::OK) { + RCLCPP_ERROR_STREAM( + this->get_logger(), + "Given Calibration File: '" << calibration_configuration.calibration_file << "'"); + return cal_status; + } + } + + RCLCPP_INFO_STREAM(this->get_logger(), "SensorConfig:" << sensor_configuration); + return Status::OK; +} + +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; + } +} + +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 checkPCDs(nebula::drivers::NebulaPointCloudPtr pp1, pcl::PointCloud::Ptr 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); + } +} + +void VelodyneRosDecoderTest::ReadBag() +{ + rosbag2_storage::StorageOptions storage_options; + rosbag2_cpp::ConverterOptions converter_options; + + std::cout << bag_path << std::endl; + std::cout << storage_id << std::endl; + std::cout << format << std::endl; + std::cout << target_topic << std::endl; + + auto target_topic_name = target_topic; + if (target_topic_name.substr(0, 1) == "/") { + target_topic_name = target_topic_name.substr(1); + } + target_topic_name = std::regex_replace(target_topic_name, std::regex("/"), "_"); + + pcl::PCDReader pcd_reader; + + rcpputils::fs::path bag_dir(bag_path); + rcpputils::fs::path pcd_dir = bag_dir.parent_path(); + int check_cnt = 0; + + storage_options.uri = bag_path; + storage_options.storage_id = storage_id; + converter_options.output_serialization_format = format; //"cdr"; + rclcpp::Serialization serialization; + nebula::drivers::NebulaPointCloudPtr pointcloud(new nebula::drivers::NebulaPointCloud); + // nebula::drivers::NebulaPointCloudPtr ref_pointcloud(new nebula::drivers::NebulaPointCloud); + pcl::PointCloud::Ptr ref_pointcloud(new pcl::PointCloud); + { + rosbag2_cpp::Reader bag_reader(std::make_unique()); + bag_reader.open(storage_options, converter_options); + while (bag_reader.has_next()) { + auto bag_message = bag_reader.read_next(); + + std::cout << "Found topic name " << bag_message->topic_name << std::endl; + + if (bag_message->topic_name == target_topic) { + velodyne_msgs::msg::VelodyneScan extracted_msg; + rclcpp::SerializedMessage extracted_serialized_msg(*bag_message->serialized_data); + serialization.deserialize_message(&extracted_serialized_msg, &extracted_msg); + + std::cout << "Found data in topic " << bag_message->topic_name << ": " + << bag_message->time_stamp << std::endl; + + auto extracted_msg_ptr = std::make_shared(extracted_msg); + auto pointcloud_ts = driver_ptr_->ConvertScanToPointcloud(extracted_msg_ptr); + pointcloud = std::get<0>(pointcloud_ts); + + // There are very rare cases where has_scanned_ does not become true, but it is not known + // whether it is because of decoder or deserialize_message. + if (!pointcloud) continue; + + auto fn = std::to_string(bag_message->time_stamp) + ".pcd"; + + auto target_pcd_path = (pcd_dir / fn); + std::cout << target_pcd_path << std::endl; + + if (target_pcd_path.exists()) { + std::cout << "exists: " << target_pcd_path << std::endl; + auto rt = pcd_reader.read(target_pcd_path.string(), *ref_pointcloud); + std::cout << rt << " loaded: " << target_pcd_path << std::endl; + checkPCDs(pointcloud, ref_pointcloud); + check_cnt++; + // ref_pointcloud.reset(new nebula::drivers::NebulaPointCloud); + ref_pointcloud.reset(new pcl::PointCloud); + } + pointcloud.reset(new nebula::drivers::NebulaPointCloud); + } + } + EXPECT_GT(check_cnt, 0); + // close on scope exit + } +} + +} // namespace ros +} // namespace nebula diff --git a/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp32.hpp b/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp32.hpp new file mode 100644 index 000000000..2b889358e --- /dev/null +++ b/nebula_tests/velodyne/velodyne_ros_decoder_test_vlp32.hpp @@ -0,0 +1,91 @@ +#ifndef NEBULA_VelodyneRosDecoderTestVlp16_H +#define NEBULA_VelodyneRosDecoderTestVlp16_H + +#include "nebula_common/nebula_common.hpp" +#include "nebula_common/nebula_status.hpp" +#include "nebula_common/velodyne/velodyne_common.hpp" +#include "nebula_decoders/nebula_decoders_velodyne/velodyne_driver.hpp" +#include "nebula_ros/common/nebula_driver_ros_wrapper_base.hpp" + +#include +#include +#include + +#include +#include + +#include + +namespace nebula +{ +namespace ros +{ +/// @brief Testing decoder of VLP16 (Keeps VelodyneDriverRosWrapper structure as much as possible) +class VelodyneRosDecoderTest final : public rclcpp::Node, + NebulaDriverRosWrapperBase //, testing::Test +{ + std::shared_ptr driver_ptr_; + Status wrapper_status_; + + std::shared_ptr calibration_cfg_ptr_; + std::shared_ptr sensor_cfg_ptr_; + + /// @brief Initializing ros wrapper + /// @param sensor_configuration SensorConfiguration for this driver + /// @param calibration_configuration CalibrationConfiguration for this driver + /// @return Resulting status + Status InitializeDriver( + std::shared_ptr sensor_configuration, + std::shared_ptr calibration_configuration) override; + + /// @brief Get configurations (Magic numbers for VLP16 is described, each function can be + /// integrated if the ros parameter can be passed to Google Test) + /// @param sensor_configuration Output of SensorConfiguration + /// @param calibration_configuration Output of CalibrationConfiguration + /// @return Resulting status + Status GetParameters( + drivers::VelodyneSensorConfiguration & sensor_configuration, + drivers::VelodyneCalibrationConfiguration & calibration_configuration); + + /// @brief Convert seconds to chrono::nanoseconds + /// @param seconds + /// @return chrono::nanoseconds + static inline std::chrono::nanoseconds SecondsToChronoNanoSeconds(const double seconds) + { + return std::chrono::duration_cast( + std::chrono::duration(seconds)); + } + +public: + explicit VelodyneRosDecoderTest( + const rclcpp::NodeOptions & options, const std::string & node_name); + + /// @brief Get current status of this driver + /// @return Current status + Status GetStatus(); + + /// @brief Read the specified bag file and compare the constructed point clouds with the + /// corresponding PCD files + void ReadBag(); + /* + void SetUp() override { + // Setup things that should occur before every test instance should go here + RCLCPP_ERROR_STREAM(this->get_logger(), "DONE WITH SETUP!!"); + } + + void TearDown() override { + std::cout << "DONE WITH TEARDOWN" << std::endl; + } +*/ +private: + std::string bag_path; + std::string storage_id; + std::string format; + std::string target_topic; + std::string correction_file_path; +}; + +} // namespace ros +} // namespace nebula + +#endif // NEBULA_VelodyneRosDecoderTestVlp16_H