Skip to content

Commit

Permalink
refactor(autoware_pointcloud_preprocessor): rework pointcloud accumul…
Browse files Browse the repository at this point in the history
…ator parameters (autowarefoundation#8487)

* feat: rework pointcloud accumulator parameters

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

* chore: add explicit cast

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

* chore: add boundary

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

---------

Signed-off-by: vividf <[email protected]>
Signed-off-by: Batuhan Beytekin <[email protected]>
  • Loading branch information
vividf authored and batuhanbeytekin committed Sep 12, 2024
1 parent 6860be8 commit 9b1daf0
Show file tree
Hide file tree
Showing 7 changed files with 70 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 @@ -77,7 +77,7 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED
src/passthrough_filter/passthrough_filter_node.cpp
src/passthrough_filter/passthrough_filter_uint16_node.cpp
src/passthrough_filter/passthrough_uint16.cpp
src/pointcloud_accumulator/pointcloud_accumulator_nodelet.cpp
src/pointcloud_accumulator/pointcloud_accumulator_node.cpp
src/vector_map_filter/lanelet2_map_filter_node.cpp
src/distortion_corrector/distortion_corrector.cpp
src/distortion_corrector/distortion_corrector_node.cpp
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
/**:
ros__parameters:
accumulation_time_sec: 2.0
pointcloud_buffer_size: 50
Original file line number Diff line number Diff line change
Expand Up @@ -24,10 +24,7 @@ The `pointcloud_accumulator` is a node that accumulates pointclouds for a given

### Core Parameters

| Name | Type | Default Value | Description |
| ------------------------ | ------ | ------------- | ----------------------- |
| `accumulation_time_sec` | double | 2.0 | accumulation period [s] |
| `pointcloud_buffer_size` | int | 50 | buffer size |
{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/pointcloud_accumulator_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__POINTCLOUD_ACCUMULATOR__POINTCLOUD_ACCUMULATOR_NODELET_HPP_ // NOLINT
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__POINTCLOUD_ACCUMULATOR__POINTCLOUD_ACCUMULATOR_NODELET_HPP_ // NOLINT
#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__POINTCLOUD_ACCUMULATOR__POINTCLOUD_ACCUMULATOR_NODE_HPP_ // NOLINT
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__POINTCLOUD_ACCUMULATOR__POINTCLOUD_ACCUMULATOR_NODE_HPP_ // NOLINT

#include "autoware/pointcloud_preprocessor/filter.hpp"

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

// clang-format off
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__POINTCLOUD_ACCUMULATOR__POINTCLOUD_ACCUMULATOR_NODELET_HPP_ // NOLINT
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__POINTCLOUD_ACCUMULATOR__POINTCLOUD_ACCUMULATOR_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"/>
<arg name="output_topic_name" default="/sensing/lidar/top/pointcloud_accumulated"/>
<arg name="input_frame" default="base_link"/>
<arg name="output_frame" default="base_link"/>
<arg name="pointcloud_accumulator_param_file" default="$(find-pkg-share autoware_pointcloud_preprocessor)/config/pointcloud_accumulator_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="pointcloud_accumulator_node" name="pointcloud_accumulator_node">
<param from="$(var pointcloud_accumulator_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,40 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for Pointcloud Accumulator Node",
"type": "object",
"definitions": {
"pointcloud_accumulator": {
"type": "object",
"properties": {
"accumulation_time_sec": {
"type": "number",
"description": "accumulation period [s]",
"default": "2.0",
"minimum": 0
},
"pointcloud_buffer_size": {
"type": "integer",
"description": "buffer size",
"default": "50",
"minimum": 0
}
},
"required": ["accumulation_time_sec", "pointcloud_buffer_size"],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/pointcloud_accumulator"
}
},
"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/pointcloud_accumulator/pointcloud_accumulator_nodelet.hpp"
#include "autoware/pointcloud_preprocessor/pointcloud_accumulator/pointcloud_accumulator_node.hpp"

#include <vector>

Expand All @@ -23,9 +23,9 @@ PointcloudAccumulatorComponent::PointcloudAccumulatorComponent(const rclcpp::Nod
{
// set initial parameters
{
accumulation_time_sec_ = static_cast<double>(declare_parameter("accumulation_time_sec", 2.0));
accumulation_time_sec_ = declare_parameter<double>("accumulation_time_sec");
pointcloud_buffer_.set_capacity(
static_cast<size_t>(declare_parameter("pointcloud_buffer_size", 50)));
static_cast<size_t>(declare_parameter<int64_t>("pointcloud_buffer_size")));
}

using std::placeholders::_1;
Expand Down

0 comments on commit 9b1daf0

Please sign in to comment.