Skip to content

Commit

Permalink
feat: rework radius search 2d outlier filter parameters
Browse files Browse the repository at this point in the history
Signed-off-by: vividf <[email protected]>
  • Loading branch information
vividf committed Aug 14, 2024
1 parent 142795a commit a3b9cb1
Show file tree
Hide file tree
Showing 7 changed files with 66 additions and 11 deletions.
2 changes: 1 addition & 1 deletion sensing/autoware_pointcloud_preprocessor/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED
src/downsample_filter/pickup_based_voxel_grid_downsample_filter.cpp
src/outlier_filter/ring_outlier_filter_nodelet.cpp
src/outlier_filter/voxel_grid_outlier_filter_nodelet.cpp
src/outlier_filter/radius_search_2d_outlier_filter_nodelet.cpp
src/outlier_filter/radius_search_2d_outlier_filter_node.cpp
src/outlier_filter/dual_return_outlier_filter_nodelet.cpp
src/passthrough_filter/passthrough_filter_nodelet.cpp
src/passthrough_filter/passthrough_filter_uint16_nodelet.cpp
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
/**:
ros__parameters:
min_neighbors: 5
search_radius: 0.2
Original file line number Diff line number Diff line change
Expand Up @@ -24,10 +24,7 @@ This implementation inherits `autoware::pointcloud_preprocessor::Filter` class,

### Core Parameters

| Name | Type | Description |
| --------------- | ------ | ------------------------------------------------------------------------------------------------------------------------ |
| `min_neighbors` | int | If points in the circle centered on reference point is less than `min_neighbors`, a reference point is judged as outlier |
| `search_radius` | double | Searching number of points included in `search_radius` |
{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/radius_search_2d_outlier_filter_node.schema.json") }}

## Assumptions / Known limits

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RADIUS_SEARCH_2D_OUTLIER_FILTER_NODELET_HPP_ // NOLINT
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RADIUS_SEARCH_2D_OUTLIER_FILTER_NODELET_HPP_ // NOLINT
#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RADIUS_SEARCH_2D_OUTLIER_FILTER_NODE_HPP_ // NOLINT
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RADIUS_SEARCH_2D_OUTLIER_FILTER_NODE_HPP_ // NOLINT

#include "autoware/pointcloud_preprocessor/filter.hpp"

Expand Down Expand Up @@ -55,5 +55,5 @@ class RadiusSearch2DOutlierFilterComponent : public autoware::pointcloud_preproc
} // namespace autoware::pointcloud_preprocessor

// clang-format off
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RADIUS_SEARCH_2D_OUTLIER_FILTER_NODELET_HPP_ // NOLINT
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RADIUS_SEARCH_2D_OUTLIER_FILTER_NODE_HPP_ // NOLINT
// clang-format on
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_filtered"/>
<arg name="input_frame" default="base_link"/>
<arg name="output_frame" default="base_link"/>
<arg name="radius_search_2d_outlier_filter_param_file" default="$(find-pkg-share autoware_pointcloud_preprocessor)/config/radius_search_2d_outlier_filter_node.param.yaml"/>
<arg name="filter_param_file" default="$(find-pkg-share autoware_pointcloud_preprocessor)/config/filter.param.yaml"/>
<node pkg="autoware_pointcloud_preprocessor" exec="radius_search_2d_outlier_filter_node" name="radius_search_2d_outlier_filter_node">
<param from="$(var radius_search_2d_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,38 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for Radius Search 2D Outlier Filter Node",
"type": "object",
"definitions": {
"crop_box_filter": {
"type": "object",
"properties": {
"min_neighbors": {
"type": "integer",
"description": "If points in the circle centered on reference point is less than min_neighbors, a reference point is judged as outlier",
"default": "5"
},
"search_radius": {
"type": "number",
"description": "Searching number of points included in search_radius",
"default": "0.2"
}
},
"required": ["min_neighbors", "search_radius"],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/radius_search_2d_outlier_filter"
}
},
"required": ["ros__parameters"],
"additionalProperties": false
}
},
"required": ["/**"],
"additionalProperties": false
}
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "autoware/pointcloud_preprocessor/outlier_filter/radius_search_2d_outlier_filter_nodelet.hpp"
#include "autoware/pointcloud_preprocessor/outlier_filter/radius_search_2d_outlier_filter_node.hpp"

#include <pcl/kdtree/kdtree_flann.h>
#include <pcl/search/kdtree.h>
Expand All @@ -28,8 +28,8 @@ RadiusSearch2DOutlierFilterComponent::RadiusSearch2DOutlierFilterComponent(
{
// set initial parameters
{
min_neighbors_ = static_cast<size_t>(declare_parameter("min_neighbors", 5));
search_radius_ = static_cast<double>(declare_parameter("search_radius", 0.2));
min_neighbors_ = declare_parameter<int64_t>("min_neighbors");
search_radius_ = declare_parameter<double>("search_radius");
}

kd_tree_ = pcl::make_shared<pcl::search::KdTree<pcl::PointXY>>(false);
Expand Down

0 comments on commit a3b9cb1

Please sign in to comment.