Skip to content

Commit 8b23f9a

Browse files
vividfkyoichi-sugahara
authored andcommitted
refactor(autoware_pointcloud_preprocessor): rework lanelet2 map filter parameters (autowarefoundation#8491)
* feat: rework lanelet2 map filter parameters Signed-off-by: vividf <yihsiang.fang@tier4.jp> * chore: remove unrelated files Signed-off-by: vividf <yihsiang.fang@tier4.jp> * fix: fix node name in launch Signed-off-by: vividf <yihsiang.fang@tier4.jp> * chore: fix launcher Signed-off-by: vividf <yihsiang.fang@tier4.jp> * chore: fix spell error Signed-off-by: vividf <yihsiang.fang@tier4.jp> * chore: add boundary Signed-off-by: vividf <yihsiang.fang@tier4.jp> --------- Signed-off-by: vividf <yihsiang.fang@tier4.jp>
1 parent bc1ae4b commit 8b23f9a

File tree

7 files changed

+66
-13
lines changed

7 files changed

+66
-13
lines changed

sensing/autoware_pointcloud_preprocessor/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -78,7 +78,7 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED
7878
src/passthrough_filter/passthrough_filter_uint16_nodelet.cpp
7979
src/passthrough_filter/passthrough_uint16.cpp
8080
src/pointcloud_accumulator/pointcloud_accumulator_nodelet.cpp
81-
src/vector_map_filter/lanelet2_map_filter_nodelet.cpp
81+
src/vector_map_filter/lanelet2_map_filter_node.cpp
8282
src/distortion_corrector/distortion_corrector.cpp
8383
src/distortion_corrector/distortion_corrector_node.cpp
8484
src/blockage_diag/blockage_diag_node.cpp
Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
/**:
2+
ros__parameters:
3+
voxel_size_x: 0.04
4+
voxel_size_y: 0.04

sensing/autoware_pointcloud_preprocessor/docs/vector-map-filter.md

Lines changed: 1 addition & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -25,10 +25,7 @@ The `vector_map_filter` is a node that removes points on the outside of lane by
2525

2626
### Core Parameters
2727

28-
| Name | Type | Default Value | Description |
29-
| -------------- | ------ | ------------- | ----------- |
30-
| `voxel_size_x` | double | 0.04 | voxel size |
31-
| `voxel_size_y` | double | 0.04 | voxel size |
28+
{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/lanelet2_map_filter_node.schema.json") }}
3229

3330
## Assumptions / Known limits
3431

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2020 Tier IV, Inc.
1+
// Copyright 2024 TIER IV, Inc.
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.
@@ -12,8 +12,8 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__LANELET2_MAP_FILTER_NODELET_HPP_
16-
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__LANELET2_MAP_FILTER_NODELET_HPP_
15+
#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__LANELET2_MAP_FILTER_NODE_HPP_
16+
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__LANELET2_MAP_FILTER_NODE_HPP_
1717

1818
#include <autoware/universe_utils/geometry/boost_geometry.hpp>
1919
#include <autoware_lanelet2_extension/utility/message_conversion.hpp>
@@ -97,4 +97,4 @@ class Lanelet2MapFilterComponent : public rclcpp::Node
9797

9898
} // namespace autoware::pointcloud_preprocessor
9999

100-
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__LANELET2_MAP_FILTER_NODELET_HPP_
100+
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__LANELET2_MAP_FILTER_NODE_HPP_
Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
<launch>
2+
<arg name="input_vector_map" default="/map/vector_map"/>
3+
<arg name="input_pointcloud" default="detection_area/pointcloud"/>
4+
<arg name="output_pointcloud" default="vector_map_filtered/pointcloud"/>
5+
<arg name="lanelet2_map_filter_param_file" default="$(find-pkg-share autoware_pointcloud_preprocessor)/config/lanelet2_map_filter_node.param.yaml"/>
6+
<node pkg="autoware_pointcloud_preprocessor" exec="vector_map_filter_node" name="vector_map_filter_node">
7+
<param from="$(var lanelet2_map_filter_param_file)"/>
8+
<remap from="input/vector_map" to="$(var input_vector_map)"/>
9+
<remap from="input/pointcloud" to="$(var input_pointcloud)"/>
10+
<remap from="output" to="$(var output_pointcloud)"/>
11+
</node>
12+
</launch>
Lines changed: 40 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,40 @@
1+
{
2+
"$schema": "http://json-schema.org/draft-07/schema#",
3+
"title": "Parameters for Lanelet2 Map Filter Node",
4+
"type": "object",
5+
"definitions": {
6+
"lanelet2_map_filter": {
7+
"type": "object",
8+
"properties": {
9+
"voxel_size_x": {
10+
"type": "number",
11+
"description": "voxel size along x-axis [m]",
12+
"default": "0.04",
13+
"minimum": 0
14+
},
15+
"voxel_size_y": {
16+
"type": "number",
17+
"description": "voxel size along y-axis [m]",
18+
"default": "0.04",
19+
"minimum": 0
20+
}
21+
},
22+
"required": ["voxel_size_x", "voxel_size_y"],
23+
"additionalProperties": false
24+
}
25+
},
26+
"properties": {
27+
"/**": {
28+
"type": "object",
29+
"properties": {
30+
"ros__parameters": {
31+
"$ref": "#/definitions/lanelet2_map_filter"
32+
}
33+
},
34+
"required": ["ros__parameters"],
35+
"additionalProperties": false
36+
}
37+
},
38+
"required": ["/**"],
39+
"additionalProperties": false
40+
}

sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_nodelet.cpp renamed to sensing/autoware_pointcloud_preprocessor/src/vector_map_filter/lanelet2_map_filter_node.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2020 Tier IV, Inc.
1+
// Copyright 2024 TIER IV, Inc.
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.
@@ -12,7 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "autoware/pointcloud_preprocessor/vector_map_filter/lanelet2_map_filter_nodelet.hpp"
15+
#include "autoware/pointcloud_preprocessor/vector_map_filter/lanelet2_map_filter_node.hpp"
1616

1717
#include "autoware/pointcloud_preprocessor/filter.hpp"
1818

@@ -39,8 +39,8 @@ Lanelet2MapFilterComponent::Lanelet2MapFilterComponent(const rclcpp::NodeOptions
3939

4040
// Set parameters
4141
{
42-
voxel_size_x_ = declare_parameter("voxel_size_x", 0.04);
43-
voxel_size_y_ = declare_parameter("voxel_size_y", 0.04);
42+
voxel_size_x_ = declare_parameter<float>("voxel_size_x");
43+
voxel_size_y_ = declare_parameter<float>("voxel_size_y");
4444
}
4545

4646
// Set publisher

0 commit comments

Comments
 (0)