From a2cf149d7eef6704a055f45099edc20b01a977d7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mehmet=20Emin=20BA=C5=9EO=C4=9ELU?= Date: Fri, 23 Feb 2024 14:00:11 +0300 Subject: [PATCH] chore: tidy up --- .../include/nebula_common/velodyne/velodyne_common.hpp | 10 +++++++--- .../decoders/velodyne_scan_decoder.hpp | 5 +++-- nebula_ros/launch/velodyne_launch_all_hw.xml | 4 ++-- 3 files changed, 12 insertions(+), 7 deletions(-) diff --git a/nebula_common/include/nebula_common/velodyne/velodyne_common.hpp b/nebula_common/include/nebula_common/velodyne/velodyne_common.hpp index aba0163e2..b629fb5b4 100644 --- a/nebula_common/include/nebula_common/velodyne/velodyne_common.hpp +++ b/nebula_common/include/nebula_common/velodyne/velodyne_common.hpp @@ -12,8 +12,10 @@ namespace nebula namespace drivers { -/// @brief Invalid region on the cloud to be removed -struct InvalidRegion { +/// @brief Invalid region on the cloud to be removed. `start` and `end` represent angles of the +/// region. +struct InvalidRegion +{ uint16_t start; uint16_t end; }; @@ -27,7 +29,9 @@ struct VelodyneSensorConfiguration : LidarConfigurationBase uint16_t cloud_min_angle; uint16_t cloud_max_angle; bool invalid_point_remove; - std::map> invalid_regions; + std::map> + invalid_regions; // Key holds the channel id, value holds invalid regions belong to that + // channel }; /// @brief Convert VelodyneSensorConfiguration to string (Overloading the << operator) /// @param os 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 04732fddc..92a393ef8 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 @@ -183,8 +183,9 @@ class VelodyneScanDecoder /// @brief Resetting overflowed point cloud buffer virtual void reset_overflow(double time_stamp) = 0; - /// @brief Checks if the point is invalid. - /// @param point The point to check. + /// @brief Checks if the point is inside invalid regions. + /// @param channel Channel id of the point. + /// @param azimuth Azimuth angle of the point. /// @return True if the point is invalid, false otherwise. bool check_invalid_point(const int & channel, const uint16_t & azimuth) { diff --git a/nebula_ros/launch/velodyne_launch_all_hw.xml b/nebula_ros/launch/velodyne_launch_all_hw.xml index ddfc4e047..58f2f6050 100644 --- a/nebula_ros/launch/velodyne_launch_all_hw.xml +++ b/nebula_ros/launch/velodyne_launch_all_hw.xml @@ -19,9 +19,9 @@ - + + default="'[[0, 3500, 6900], [1, 3400, 6500], [2, 3200, 4600], [3, 3200, 4600]]'"/>