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 voxel grid outlier filter parameters #8476

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion sensing/autoware_pointcloud_preprocessor/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED
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/voxel_grid_outlier_filter_nodelet.cpp
src/outlier_filter/voxel_grid_outlier_filter_node.cpp
src/outlier_filter/radius_search_2d_outlier_filter_nodelet.cpp
src/outlier_filter/dual_return_outlier_filter_nodelet.cpp
src/passthrough_filter/passthrough_filter_nodelet.cpp
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
/**:
ros__parameters:
voxel_size_x: 0.3
voxel_size_y: 0.3
voxel_size_z: 0.1
voxel_points_threshold: 2
Original file line number Diff line number Diff line change
Expand Up @@ -23,12 +23,7 @@ This implementation inherits `autoware::pointcloud_preprocessor::Filter` class,

### Core Parameters

| Name | Type | Default Value | Description |
| ------------------------ | ------ | ------------- | ------------------------------------------ |
| `voxel_size_x` | double | 0.3 | the voxel size along x-axis [m] |
| `voxel_size_y` | double | 0.3 | the voxel size along y-axis [m] |
| `voxel_size_z` | double | 0.1 | the voxel size along z-axis [m] |
| `voxel_points_threshold` | int | 2 | the minimum number of points in each voxel |
{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/voxel_grid_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__VOXEL_GRID_OUTLIER_FILTER_NODELET_HPP_
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__VOXEL_GRID_OUTLIER_FILTER_NODELET_HPP_
#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__VOXEL_GRID_OUTLIER_FILTER_NODE_HPP_
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__VOXEL_GRID_OUTLIER_FILTER_NODE_HPP_

#include "autoware/pointcloud_preprocessor/filter.hpp"

Expand Down Expand Up @@ -50,4 +50,4 @@ class VoxelGridOutlierFilterComponent : public autoware::pointcloud_preprocessor
};
} // namespace autoware::pointcloud_preprocessor

#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__VOXEL_GRID_OUTLIER_FILTER_NODELET_HPP_
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__VOXEL_GRID_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="/pointcloud_raw"/>
<arg name="output_topic_name" default="/pointcloud_filtered"/>
<arg name="input_frame" default=""/>
<arg name="output_frame" default=""/>
<arg name="voxel_grid_outlier_filter_param_file" default="$(find-pkg-share autoware_pointcloud_preprocessor)/config/voxel_grid_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="voxel_grid_outlier_filter_node" name="voxel_grid_outlier_filter_node">
<param from="$(var voxel_grid_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,52 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for Voxel Grid Outlier Filter Node",
"type": "object",
"definitions": {
"voxel_grid_outlier_filter": {
"type": "object",
"properties": {
"voxel_size_x": {
"type": "number",
"description": "the voxel size along x-axis [m]",
"default": "0.3",
"minimum": 0
},
"voxel_size_y": {
"type": "number",
"description": "the voxel size along y-axis [m]",
"default": "0.3",
"minimum": 0
},
"voxel_size_z": {
"type": "number",
"description": "the voxel size along z-axis [m]",
"default": "0.1",
"minimum": 0
},
"voxel_points_threshold": {
"type": "integer",
"description": "the minimum number of points in each voxel",
"default": "2",
"minimum": 1
}
},
"required": ["voxel_size_x", "voxel_size_y", "voxel_size_z", "voxel_points_threshold"],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/voxel_grid_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/voxel_grid_outlier_filter_nodelet.hpp"
#include "autoware/pointcloud_preprocessor/outlier_filter/voxel_grid_outlier_filter_node.hpp"

#include <pcl/kdtree/kdtree_flann.h>
#include <pcl/search/kdtree.h>
Expand All @@ -28,10 +28,10 @@ VoxelGridOutlierFilterComponent::VoxelGridOutlierFilterComponent(
{
// set initial parameters
{
voxel_size_x_ = static_cast<double>(declare_parameter("voxel_size_x", 0.3));
voxel_size_y_ = static_cast<double>(declare_parameter("voxel_size_y", 0.3));
voxel_size_z_ = static_cast<double>(declare_parameter("voxel_size_z", 0.1));
voxel_points_threshold_ = static_cast<int>(declare_parameter("voxel_points_threshold", 2));
voxel_size_x_ = declare_parameter<double>("voxel_size_x");
voxel_size_y_ = declare_parameter<double>("voxel_size_y");
voxel_size_z_ = declare_parameter<double>("voxel_size_z");
voxel_points_threshold_ = declare_parameter<int>("voxel_points_threshold");
}

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