Skip to content

Commit

Permalink
refactor: rename filter parameter name
Browse files Browse the repository at this point in the history
  • Loading branch information
mebasoglu committed Apr 16, 2024
1 parent 0aa148f commit 847c1a7
Show file tree
Hide file tree
Showing 3 changed files with 15 additions and 15 deletions.
22 changes: 11 additions & 11 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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]`.
Expand All @@ -235,7 +235,7 @@ Parameters shared by all supported models:
<node pkg="nebula_ros" exec="velodyne_driver_ros_wrapper_node"
name="velodyne_cloud" output="screen">
...
<param name="ring_section_filter" value="true"/>
<param name="enable_ring_section_filter" value="true"/>
<param name="excluded_ring_sectors" type="str"
value="[0, 3500, 6900], [1, 3400, 6500], [2, 3200, 4600], [3, 3200, 4600]"/>
</node>
Expand Down
4 changes: 2 additions & 2 deletions nebula_ros/launch/velodyne_launch_all_hw.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

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

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

Expand All @@ -30,7 +30,7 @@
<param name="frame_id" value="$(var frame_id)"/>
<param name="scan_phase" value="$(var scan_phase)"/>
<param name="calibration_file" value="$(var calibration_file)"/>
<param name="ring_section_filter" value="$(var ring_section_filter)"/>
<param name="enable_ring_section_filter" value="$(var enable_ring_section_filter)"/>
<param name="excluded_ring_sectors" type="str" value="$(var excluded_ring_sectors)"/>
</node>

Expand Down
4 changes: 2 additions & 2 deletions nebula_ros/src/velodyne/velodyne_decoder_ros_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -252,9 +252,9 @@ Status VelodyneDriverRosWrapper::GetParameters(
descriptor.read_only = false;
descriptor.dynamic_typing = false;
descriptor.additional_constraints = "";
this->declare_parameter<bool>("ring_section_filter", false, descriptor);
this->declare_parameter<bool>("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 {
Expand Down

0 comments on commit 847c1a7

Please sign in to comment.