From 847c1a7bde23076369b6e4107297af2fd7a62190 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Mehmet=20Emin=20BA=C5=9EO=C4=9ELU?= Date: Tue, 16 Apr 2024 17:46:25 +0300 Subject: [PATCH] refactor: rename filter parameter name --- README.md | 22 +++++++++---------- nebula_ros/launch/velodyne_launch_all_hw.xml | 4 ++-- .../velodyne/velodyne_decoder_ros_wrapper.cpp | 4 ++-- 3 files changed, 15 insertions(+), 15 deletions(-) diff --git a/README.md b/README.md index 3c0302b49..234a9990f 100644 --- a/README.md +++ b/README.md @@ -214,16 +214,16 @@ Parameters shared by all supported models: #### Driver parameters -| Parameter | Type | Default | Accepted values | Description | -|-----------------------|--------|----------|------------------|------------------------------------------------------------------------------------------------------------------------------------| -| frame_id | string | velodyne | | ROS frame ID | -| calibration_file | string | | | LiDAR calibration file | -| min_range | double | 0.3 | meters, >= 0.3 | Minimum point range published | -| max_range | double | 300.0 | meters, <= 300.0 | Maximum point range published | -| cloud_min_angle | uint16 | 0 | degrees [0, 360] | FoV start angle | -| cloud_max_angle | uint16 | 359 | degrees [0, 360] | FoV end angle | -| ring_section_filter | bool | false | true, false | Toggles filtering out specific ring sectors. | -| excluded_ring_sectors | string | | | Identifies and prevents specific ring sectors from being included in the point cloud based on ring ID, start angle, and end angle. | +| Parameter | Type | Default | Accepted values | Description | +|----------------------------|--------|----------|------------------|------------------------------------------------------------------------------------------------------------------------------------| +| frame_id | string | velodyne | | ROS frame ID | +| calibration_file | string | | | LiDAR calibration file | +| min_range | double | 0.3 | meters, >= 0.3 | Minimum point range published | +| max_range | double | 300.0 | meters, <= 300.0 | Maximum point range published | +| cloud_min_angle | uint16 | 0 | degrees [0, 360] | FoV start angle | +| cloud_max_angle | uint16 | 359 | degrees [0, 360] | FoV end angle | +| enable_ring_section_filter | bool | false | true, false | Toggles filtering out specific ring sectors. | +| excluded_ring_sectors | string | | | Identifies and prevents specific ring sectors from being included in the point cloud based on ring ID, start angle, and end angle. | - `enable_ring_section_filter` toggles a ring-based filter to remove points located within predefined angle ranges. - Specify an excluded section using the format `[ring_id, start_angle, end_angle]`. @@ -235,7 +235,7 @@ Parameters shared by all supported models: ... - + diff --git a/nebula_ros/launch/velodyne_launch_all_hw.xml b/nebula_ros/launch/velodyne_launch_all_hw.xml index 6d0a9acc9..78218773b 100644 --- a/nebula_ros/launch/velodyne_launch_all_hw.xml +++ b/nebula_ros/launch/velodyne_launch_all_hw.xml @@ -19,7 +19,7 @@ - + @@ -30,7 +30,7 @@ - + diff --git a/nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp b/nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp index 538cb52c8..8423c0e83 100644 --- a/nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp +++ b/nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp @@ -252,9 +252,9 @@ Status VelodyneDriverRosWrapper::GetParameters( descriptor.read_only = false; descriptor.dynamic_typing = false; descriptor.additional_constraints = ""; - this->declare_parameter("ring_section_filter", false, descriptor); + this->declare_parameter("enable_ring_section_filter", false, descriptor); sensor_configuration.ring_section_filter = - this->get_parameter("ring_section_filter").as_bool(); + this->get_parameter("enable_ring_section_filter").as_bool(); if (sensor_configuration.ring_section_filter) { RCLCPP_DEBUG_STREAM(this->get_logger(), "Ring section filter is active."); } else {