Skip to content

Commit

Permalink
refactor(autoware_pointcloud_preprocessor): rework lanelet2 map filte…
Browse files Browse the repository at this point in the history
…r 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>
  • Loading branch information
vividf committed Aug 22, 2024
1 parent cf6859e commit 44e0535
Show file tree
Hide file tree
Showing 7 changed files with 66 additions and 13 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 @@ -78,7 +78,7 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED
src/passthrough_filter/passthrough_filter_uint16_nodelet.cpp
src/passthrough_filter/passthrough_uint16.cpp
src/pointcloud_accumulator/pointcloud_accumulator_nodelet.cpp
src/vector_map_filter/lanelet2_map_filter_nodelet.cpp
src/vector_map_filter/lanelet2_map_filter_node.cpp
src/distortion_corrector/distortion_corrector.cpp
src/distortion_corrector/distortion_corrector_node.cpp
src/blockage_diag/blockage_diag_node.cpp
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
/**:
ros__parameters:
voxel_size_x: 0.04
voxel_size_y: 0.04
Original file line number Diff line number Diff line change
Expand Up @@ -25,10 +25,7 @@ The `vector_map_filter` is a node that removes points on the outside of lane by

### Core Parameters

| Name | Type | Default Value | Description |
| -------------- | ------ | ------------- | ----------- |
| `voxel_size_x` | double | 0.04 | voxel size |
| `voxel_size_y` | double | 0.04 | voxel size |
{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/lanelet2_map_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__VECTOR_MAP_FILTER__LANELET2_MAP_FILTER_NODELET_HPP_
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__LANELET2_MAP_FILTER_NODELET_HPP_
#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__LANELET2_MAP_FILTER_NODE_HPP_
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__LANELET2_MAP_FILTER_NODE_HPP_

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

} // namespace autoware::pointcloud_preprocessor

#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__LANELET2_MAP_FILTER_NODELET_HPP_
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__VECTOR_MAP_FILTER__LANELET2_MAP_FILTER_NODE_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
<launch>
<arg name="input_vector_map" default="/map/vector_map"/>
<arg name="input_pointcloud" default="detection_area/pointcloud"/>
<arg name="output_pointcloud" default="vector_map_filtered/pointcloud"/>
<arg name="lanelet2_map_filter_param_file" default="$(find-pkg-share autoware_pointcloud_preprocessor)/config/lanelet2_map_filter_node.param.yaml"/>
<node pkg="autoware_pointcloud_preprocessor" exec="vector_map_filter_node" name="vector_map_filter_node">
<param from="$(var lanelet2_map_filter_param_file)"/>
<remap from="input/vector_map" to="$(var input_vector_map)"/>
<remap from="input/pointcloud" to="$(var input_pointcloud)"/>
<remap from="output" to="$(var output_pointcloud)"/>
</node>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for Lanelet2 Map Filter Node",
"type": "object",
"definitions": {
"lanelet2_map_filter": {
"type": "object",
"properties": {
"voxel_size_x": {
"type": "number",
"description": "voxel size along x-axis [m]",
"default": "0.04",
"minimum": 0
},
"voxel_size_y": {
"type": "number",
"description": "voxel size along y-axis [m]",
"default": "0.04",
"minimum": 0
}
},
"required": ["voxel_size_x", "voxel_size_y"],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/lanelet2_map_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/vector_map_filter/lanelet2_map_filter_nodelet.hpp"
#include "autoware/pointcloud_preprocessor/vector_map_filter/lanelet2_map_filter_node.hpp"

#include "autoware/pointcloud_preprocessor/filter.hpp"

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

// Set parameters
{
voxel_size_x_ = declare_parameter("voxel_size_x", 0.04);
voxel_size_y_ = declare_parameter("voxel_size_y", 0.04);
voxel_size_x_ = declare_parameter<float>("voxel_size_x");
voxel_size_y_ = declare_parameter<float>("voxel_size_y");
}

// Set publisher
Expand Down

0 comments on commit 44e0535

Please sign in to comment.