Skip to content

Commit 847c1a7

Browse files
committed
refactor: rename filter parameter name
1 parent 0aa148f commit 847c1a7

File tree

3 files changed

+15
-15
lines changed

3 files changed

+15
-15
lines changed

README.md

+11-11
Original file line numberDiff line numberDiff line change
@@ -214,16 +214,16 @@ Parameters shared by all supported models:
214214

215215
#### Driver parameters
216216

217-
| Parameter | Type | Default | Accepted values | Description |
218-
|-----------------------|--------|----------|------------------|------------------------------------------------------------------------------------------------------------------------------------|
219-
| frame_id | string | velodyne | | ROS frame ID |
220-
| calibration_file | string | | | LiDAR calibration file |
221-
| min_range | double | 0.3 | meters, >= 0.3 | Minimum point range published |
222-
| max_range | double | 300.0 | meters, <= 300.0 | Maximum point range published |
223-
| cloud_min_angle | uint16 | 0 | degrees [0, 360] | FoV start angle |
224-
| cloud_max_angle | uint16 | 359 | degrees [0, 360] | FoV end angle |
225-
| ring_section_filter | bool | false | true, false | Toggles filtering out specific ring sectors. |
226-
| 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. |
217+
| Parameter | Type | Default | Accepted values | Description |
218+
|----------------------------|--------|----------|------------------|------------------------------------------------------------------------------------------------------------------------------------|
219+
| frame_id | string | velodyne | | ROS frame ID |
220+
| calibration_file | string | | | LiDAR calibration file |
221+
| min_range | double | 0.3 | meters, >= 0.3 | Minimum point range published |
222+
| max_range | double | 300.0 | meters, <= 300.0 | Maximum point range published |
223+
| cloud_min_angle | uint16 | 0 | degrees [0, 360] | FoV start angle |
224+
| cloud_max_angle | uint16 | 359 | degrees [0, 360] | FoV end angle |
225+
| enable_ring_section_filter | bool | false | true, false | Toggles filtering out specific ring sectors. |
226+
| 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. |
227227

228228
- `enable_ring_section_filter` toggles a ring-based filter to remove points located within predefined angle ranges.
229229
- Specify an excluded section using the format `[ring_id, start_angle, end_angle]`.
@@ -235,7 +235,7 @@ Parameters shared by all supported models:
235235
<node pkg="nebula_ros" exec="velodyne_driver_ros_wrapper_node"
236236
name="velodyne_cloud" output="screen">
237237
...
238-
<param name="ring_section_filter" value="true"/>
238+
<param name="enable_ring_section_filter" value="true"/>
239239
<param name="excluded_ring_sectors" type="str"
240240
value="[0, 3500, 6900], [1, 3400, 6500], [2, 3200, 4600], [3, 3200, 4600]"/>
241241
</node>

nebula_ros/launch/velodyne_launch_all_hw.xml

+2-2
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@
1919

2020
<arg name="setup_sensor" default="True" description="Enable sensor setup on hw-driver."/>
2121

22-
<arg name="ring_section_filter" default="false"/>
22+
<arg name="enable_ring_section_filter" default="false"/>
2323
<arg name="excluded_ring_sectors"
2424
default="[0, 3500, 6900], [1, 3400, 6500], [2, 3200, 4600], [3, 3200, 4600]"/>
2525

@@ -30,7 +30,7 @@
3030
<param name="frame_id" value="$(var frame_id)"/>
3131
<param name="scan_phase" value="$(var scan_phase)"/>
3232
<param name="calibration_file" value="$(var calibration_file)"/>
33-
<param name="ring_section_filter" value="$(var ring_section_filter)"/>
33+
<param name="enable_ring_section_filter" value="$(var enable_ring_section_filter)"/>
3434
<param name="excluded_ring_sectors" type="str" value="$(var excluded_ring_sectors)"/>
3535
</node>
3636

nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -252,9 +252,9 @@ Status VelodyneDriverRosWrapper::GetParameters(
252252
descriptor.read_only = false;
253253
descriptor.dynamic_typing = false;
254254
descriptor.additional_constraints = "";
255-
this->declare_parameter<bool>("ring_section_filter", false, descriptor);
255+
this->declare_parameter<bool>("enable_ring_section_filter", false, descriptor);
256256
sensor_configuration.ring_section_filter =
257-
this->get_parameter("ring_section_filter").as_bool();
257+
this->get_parameter("enable_ring_section_filter").as_bool();
258258
if (sensor_configuration.ring_section_filter) {
259259
RCLCPP_DEBUG_STREAM(this->get_logger(), "Ring section filter is active.");
260260
} else {

0 commit comments

Comments
 (0)