Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(autoware_pointcloud_preprocessor): rework ring outlier filter parameters #8468

Open
wants to merge 12 commits into
base: main
Choose a base branch
from
Open
2 changes: 1 addition & 1 deletion sensing/autoware_pointcloud_preprocessor/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED
src/downsample_filter/random_downsample_filter_nodelet.cpp
src/downsample_filter/approximate_downsample_filter_nodelet.cpp
src/downsample_filter/pickup_based_voxel_grid_downsample_filter.cpp
src/outlier_filter/ring_outlier_filter_nodelet.cpp
src/outlier_filter/ring_outlier_filter_node.cpp
src/outlier_filter/radius_search_2d_outlier_filter_node.cpp
src/outlier_filter/voxel_grid_outlier_filter_node.cpp
src/outlier_filter/dual_return_outlier_filter_nodelet.cpp
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
/**:
ros__parameters:
distance_ratio: 1.03
object_length_threshold: 0.1
num_points_threshold: 4
max_rings_num: 128
max_points_num_per_ring: 4000
publish_outlier_pointcloud: false
min_azimuth_deg: 0.0
max_azimuth_deg: 360.0
max_distance: 12.0
vertical_bins: 128
horizontal_bins: 36
noise_threshold: 2
Original file line number Diff line number Diff line change
Expand Up @@ -56,20 +56,7 @@ This implementation inherits `autoware::pointcloud_preprocessor::Filter` class,

### Core Parameters

| Name | Type | Default Value | Description |
| ---------------------------- | ------- | ------------- | ----------------------------------------------------------------------------------------------------------------------------- |
| `distance_ratio` | double | 1.03 | |
| `object_length_threshold` | double | 0.1 | |
| `num_points_threshold` | int | 4 | |
| `max_rings_num` | uint_16 | 128 | |
| `max_points_num_per_ring` | size_t | 4000 | Set this value large enough such that `HFoV / resolution < max_points_num_per_ring` |
| `publish_outlier_pointcloud` | bool | false | Flag to publish outlier pointcloud and visibility score. Due to performance concerns, please set to false during experiments. |
| `min_azimuth_deg` | float | 0.0 | The left limit of azimuth for visibility score calculation |
| `max_azimuth_deg` | float | 360.0 | The right limit of azimuth for visibility score calculation |
| `max_distance` | float | 12.0 | The limit distance for visibility score calculation |
| `vertical_bins` | int | 128 | The number of vertical bin for visibility histogram |
| `horizontal_bins` | int | 36 | The number of horizontal bin for visibility histogram |
| `noise_threshold` | int | 2 | The threshold value for distinguishing noise from valid points in the frequency image |
{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/ring_outlier_filter_node.schema.json") }} |

## Assumptions / Known limits

Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 Tier IV, Inc.
// Copyright 2024 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RING_OUTLIER_FILTER_NODELET_HPP_
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RING_OUTLIER_FILTER_NODELET_HPP_
#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RING_OUTLIER_FILTER_NODE_HPP_
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RING_OUTLIER_FILTER_NODE_HPP_

#include "autoware/pointcloud_preprocessor/filter.hpp"
#include "autoware/pointcloud_preprocessor/transform_info.hpp"
Expand Down Expand Up @@ -108,4 +108,4 @@ class RingOutlierFilterComponent : public autoware::pointcloud_preprocessor::Fil
};

} // namespace autoware::pointcloud_preprocessor
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RING_OUTLIER_FILTER_NODELET_HPP_
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RING_OUTLIER_FILTER_NODE_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
<launch>
<arg name="input_topic_name" default="/sensing/lidar/top/pointcloud_raw_ex"/>
<arg name="output_topic_name" default="/sensing/lidar/top/pointcloud_ring_filtered"/>
<arg name="input_frame" default=""/>
<arg name="output_frame" default=""/>
<arg name="filter_param_file" default="$(find-pkg-share autoware_pointcloud_preprocessor)/config/filter.param.yaml"/>
<arg name="ring_outlier_filter_param_file" default="$(find-pkg-share autoware_pointcloud_preprocessor)/config/ring_outlier_filter_node.param.yaml"/>
<node pkg="autoware_pointcloud_preprocessor" exec="ring_outlier_filter_node" name="ring_outlier_filter_node">
<param from="$(var ring_outlier_filter_param_file)"/>
<param from="$(var filter_param_file)"/>
<remap from="input" to="$(var input_topic_name)"/>
<remap from="output" to="$(var output_topic_name)"/>
<param name="input_frame" value="$(var input_frame)"/>
<param name="output_frame" value="$(var output_frame)"/>
</node>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,112 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for Ring Outlier Filter Node",
"type": "object",
"definitions": {
"ring_outlier_filter": {
"type": "object",
"properties": {
"distance_ratio": {
"type": "number",
"description": "distance_ratio",
"default": "1.03",
"minimum": 0
},
"object_length_threshold": {
"type": "number",
"description": "object_length_threshold",
"default": "0.1",
"minimum": 0
},
"num_points_threshold": {
"type": "integer",
"description": "num_points_threshold",
"default": "4",
"minimum": 0
},
"max_rings_num": {
"type": "integer",
"description": "max_rings_num",
"default": "128",
"minimum": 1
},
"max_points_num_per_ring": {
"type": "integer",
"description": "Set this value large enough such that HFoV / resolution < max_points_num_per_ring",
"default": "4000",
"minimum": 0
},
"publish_outlier_pointcloud": {
"type": "boolean",
"description": "Flag to publish outlier pointcloud and visibility score. Due to performance concerns, please set to false during experiments.",
"default": "false"
},
"min_azimuth_deg": {
"type": "number",
"description": "The left limit of azimuth for visibility score calculation",
"default": "0.0",
"minimum": 0
},
"max_azimuth_deg": {
knzo25 marked this conversation as resolved.
Show resolved Hide resolved
"type": "number",
"description": "The right limit of azimuth for visibility score calculation",
"default": "360.0",
"minimum": 0,
"maximum": 360
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I do not how schema handles this, but ROS2 is quite squeamish about how it parses ints and floats differently.

-> 360.0

Also, some numbers are between commas and other not. Which is the correct version? Make it consistent

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@knzo25 Thanks for the review. For the default value, from Amadeusz's suggestion, assigning the default values as strings will pass the number precisely.

Minimum and maximum values do not accept commas. Also, from the website examples and by testing local, 360 and 360.0 are the same (as they are just checking for the boundary but not related to ros2 parsing?)

},
"max_distance": {
"type": "number",
"description": "The limit distance for visibility score calculation",
"default": "12.0",
"minimum": 0
},
"vertical_bins": {
"type": "integer",
"description": "The number of vertical bin for visibility histogram",
"default": "128",
"minimum": 1
},
"horizontal_bins": {
"type": "integer",
"description": "The number of horizontal bin for visibility histogram",
"default": "36",
"minimum": 1
},
"noise_threshold": {
"type": "integer",
"description": "The threshold value for distinguishing noise from valid points in the frequency image",
"default": "2"
}
},
"required": [
"distance_ratio",
"object_length_threshold",
"num_points_threshold",
"max_rings_num",
"max_points_num_per_ring",
"publish_outlier_pointcloud",
"min_azimuth_deg",
"max_azimuth_deg",
"max_distance",
"vertical_bins",
"horizontal_bins",
"noise_threshold"
],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/ring_outlier_filter"
}
},
"required": ["ros__parameters"],
"additionalProperties": false
}
},
"required": ["/**"],
"additionalProperties": false
}
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 Tier IV, Inc.
// Copyright 2024 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_nodelet.hpp"
#include "autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_node.hpp"

#include "autoware_point_types/types.hpp"

Expand Down Expand Up @@ -47,22 +47,21 @@ RingOutlierFilterComponent::RingOutlierFilterComponent(const rclcpp::NodeOptions

// set initial parameters
{
distance_ratio_ = static_cast<double>(declare_parameter("distance_ratio", 1.03));
object_length_threshold_ =
static_cast<double>(declare_parameter("object_length_threshold", 0.1));
num_points_threshold_ = static_cast<int>(declare_parameter("num_points_threshold", 4));
max_rings_num_ = static_cast<uint16_t>(declare_parameter("max_rings_num", 128));
distance_ratio_ = declare_parameter<double>("distance_ratio");
object_length_threshold_ = declare_parameter<double>("object_length_threshold");
num_points_threshold_ = declare_parameter<int>("num_points_threshold");
max_rings_num_ = static_cast<uint16_t>(declare_parameter<int64_t>("max_rings_num"));
max_points_num_per_ring_ =
static_cast<size_t>(declare_parameter("max_points_num_per_ring", 4000));
publish_outlier_pointcloud_ =
static_cast<bool>(declare_parameter("publish_outlier_pointcloud", false));

min_azimuth_deg_ = static_cast<float>(declare_parameter("min_azimuth_deg", 0.0));
max_azimuth_deg_ = static_cast<float>(declare_parameter("max_azimuth_deg", 360.0));
max_distance_ = static_cast<float>(declare_parameter("max_distance", 12.0));
vertical_bins_ = static_cast<int>(declare_parameter("vertical_bins", 128));
horizontal_bins_ = static_cast<int>(declare_parameter("horizontal_bins", 36));
noise_threshold_ = static_cast<int>(declare_parameter("noise_threshold", 2));
static_cast<size_t>(declare_parameter<int64_t>("max_points_num_per_ring"));

publish_outlier_pointcloud_ = declare_parameter<bool>("publish_outlier_pointcloud");

min_azimuth_deg_ = declare_parameter<float>("min_azimuth_deg");
max_azimuth_deg_ = declare_parameter<float>("max_azimuth_deg");
max_distance_ = declare_parameter<float>("max_distance");
vertical_bins_ = declare_parameter<int>("vertical_bins");
horizontal_bins_ = declare_parameter<int>("horizontal_bins");
noise_threshold_ = declare_parameter<int>("noise_threshold");
}

using std::placeholders::_1;
Expand Down
Loading