Skip to content

Commit

Permalink
refactor(autoware_pointcloud_preprocessor): rework random downsample …
Browse files Browse the repository at this point in the history
…filter parameters (autowarefoundation#8485)

* feat: rework random downsample filter parameter

Signed-off-by: vividf <[email protected]>

* chore: change name

Signed-off-by: vividf <[email protected]>

* chore: add explicit cast

Signed-off-by: vividf <[email protected]>

---------

Signed-off-by: vividf <[email protected]>
Co-authored-by: Kenzo Lobos Tsunekawa <[email protected]>
Signed-off-by: Batuhan Beytekin <[email protected]>
  • Loading branch information
2 people authored and batuhanbeytekin committed Sep 12, 2024
1 parent ae2ee04 commit f7d66c9
Show file tree
Hide file tree
Showing 7 changed files with 52 additions and 17 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 @@ -67,7 +67,7 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED
src/time_synchronizer/time_synchronizer_node.cpp
src/crop_box_filter/crop_box_filter_nodelet.cpp
src/downsample_filter/voxel_grid_downsample_filter_node.cpp
src/downsample_filter/random_downsample_filter_nodelet.cpp
src/downsample_filter/random_downsample_filter_node.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
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
/**:
ros__parameters:
sample_num: 1500
Original file line number Diff line number Diff line change
Expand Up @@ -44,9 +44,7 @@ These implementations inherit `autoware::pointcloud_preprocessor::Filter` class,

### Random Downsample Filter

| Name | Type | Default Value | Description |
| ------------ | ---- | ------------- | ------------------------------- |
| `sample_num` | int | 1500 | number of indices to be sampled |
{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/random_downsample_filter_node.schema.json") }}

### Voxel Grid Downsample Filter

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 Down Expand Up @@ -48,8 +48,8 @@
*
*/

#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__RANDOM_DOWNSAMPLE_FILTER_NODELET_HPP_
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__RANDOM_DOWNSAMPLE_FILTER_NODELET_HPP_
#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__RANDOM_DOWNSAMPLE_FILTER_NODE_HPP_
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__RANDOM_DOWNSAMPLE_FILTER_NODE_HPP_

#include "autoware/pointcloud_preprocessor/filter.hpp"

Expand Down Expand Up @@ -81,5 +81,5 @@ class RandomDownsampleFilterComponent : public autoware::pointcloud_preprocessor
} // namespace autoware::pointcloud_preprocessor

// clang-format off
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__RANDOM_DOWNSAMPLE_FILTER_NODELET_HPP_ // NOLINT
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__DOWNSAMPLE_FILTER__RANDOM_DOWNSAMPLE_FILTER_NODE_HPP_ // NOLINT
// clang-format on
Original file line number Diff line number Diff line change
@@ -1,16 +1,16 @@
<launch>
<arg name="input_topic_name" default="/sensing/lidar/top/pointcloud_raw"/>
<arg name="output_topic_name" default="/sensing/lidar/top/random_downsample_filter/pointcloud"/>

<arg name="sample_num" default="1500"/>
<arg name="input_frame" default=""/>
<arg name="output_frame" default="base_link"/>
<arg name="output_frame" default=""/>
<arg name="random_downsample_filter_param_file" default="$(find-pkg-share autoware_pointcloud_preprocessor)/config/random_downsample_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="random_downsample_filter_node" name="random_downsample_filter">
<node pkg="autoware_pointcloud_preprocessor" exec="random_downsample_filter_node" name="random_downsample_filter_node">
<param from="$(var random_downsample_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="sample_num" value="$(var sample_num)"/>
<param name="input_frame" value="$(var input_frame)"/>
<param name="output_frame" value="$(var output_frame)"/>
</node>
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for Random Downsample Filter Node",
"type": "object",
"definitions": {
"random_downsample_filter": {
"type": "object",
"properties": {
"sample_num": {
"type": "integer",
"minimum": 0,
"description": "number of indices to be sampled",
"default": "1500"
}
},
"required": ["sample_num"],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/random_downsample_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 Down Expand Up @@ -46,7 +46,7 @@
*
*/

#include "autoware/pointcloud_preprocessor/downsample_filter/random_downsample_filter_nodelet.hpp"
#include "autoware/pointcloud_preprocessor/downsample_filter/random_downsample_filter_node.hpp"

#include <vector>

Expand All @@ -58,7 +58,7 @@ RandomDownsampleFilterComponent::RandomDownsampleFilterComponent(
{
// set initial parameters
{
sample_num_ = static_cast<size_t>(declare_parameter("sample_num", 1500));
sample_num_ = static_cast<size_t>(declare_parameter<int64_t>("sample_num"));
}

using std::placeholders::_1;
Expand Down

0 comments on commit f7d66c9

Please sign in to comment.