Skip to content

Commit ae2ee04

Browse files
vividfbatuhanbeytekin
authored andcommitted
refactor(autoware_pointcloud_preprocessor): rework pointcloud accumulator 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]>
1 parent 6860be8 commit ae2ee04

File tree

7 files changed

+70
-13
lines changed

7 files changed

+70
-13
lines changed

sensing/autoware_pointcloud_preprocessor/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -77,7 +77,7 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED
7777
src/passthrough_filter/passthrough_filter_node.cpp
7878
src/passthrough_filter/passthrough_filter_uint16_node.cpp
7979
src/passthrough_filter/passthrough_uint16.cpp
80-
src/pointcloud_accumulator/pointcloud_accumulator_nodelet.cpp
80+
src/pointcloud_accumulator/pointcloud_accumulator_node.cpp
8181
src/vector_map_filter/lanelet2_map_filter_node.cpp
8282
src/distortion_corrector/distortion_corrector.cpp
8383
src/distortion_corrector/distortion_corrector_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+
accumulation_time_sec: 2.0
4+
pointcloud_buffer_size: 50

sensing/autoware_pointcloud_preprocessor/docs/pointcloud-accumulator.md

Lines changed: 1 addition & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -24,10 +24,7 @@ The `pointcloud_accumulator` is a node that accumulates pointclouds for a given
2424

2525
### Core Parameters
2626

27-
| Name | Type | Default Value | Description |
28-
| ------------------------ | ------ | ------------- | ----------------------- |
29-
| `accumulation_time_sec` | double | 2.0 | accumulation period [s] |
30-
| `pointcloud_buffer_size` | int | 50 | buffer size |
27+
{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/pointcloud_accumulator_node.schema.json") }}
3128

3229
## Assumptions / Known limits
3330

sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/pointcloud_accumulator/pointcloud_accumulator_nodelet.hpp renamed to sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/pointcloud_accumulator/pointcloud_accumulator_node.hpp

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__POINTCLOUD_ACCUMULATOR__POINTCLOUD_ACCUMULATOR_NODELET_HPP_ // NOLINT
16-
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__POINTCLOUD_ACCUMULATOR__POINTCLOUD_ACCUMULATOR_NODELET_HPP_ // NOLINT
15+
#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__POINTCLOUD_ACCUMULATOR__POINTCLOUD_ACCUMULATOR_NODE_HPP_ // NOLINT
16+
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__POINTCLOUD_ACCUMULATOR__POINTCLOUD_ACCUMULATOR_NODE_HPP_ // NOLINT
1717

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

@@ -46,5 +46,5 @@ class PointcloudAccumulatorComponent : public autoware::pointcloud_preprocessor:
4646
} // namespace autoware::pointcloud_preprocessor
4747

4848
// clang-format off
49-
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__POINTCLOUD_ACCUMULATOR__POINTCLOUD_ACCUMULATOR_NODELET_HPP_ // NOLINT
49+
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__POINTCLOUD_ACCUMULATOR__POINTCLOUD_ACCUMULATOR_NODE_HPP_ // NOLINT
5050
// clang-format on
Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,16 @@
1+
<launch>
2+
<arg name="input_topic_name" default="/sensing/lidar/top/pointcloud"/>
3+
<arg name="output_topic_name" default="/sensing/lidar/top/pointcloud_accumulated"/>
4+
<arg name="input_frame" default="base_link"/>
5+
<arg name="output_frame" default="base_link"/>
6+
<arg name="pointcloud_accumulator_param_file" default="$(find-pkg-share autoware_pointcloud_preprocessor)/config/pointcloud_accumulator_node.param.yaml"/>
7+
<arg name="filter_param_file" default="$(find-pkg-share autoware_pointcloud_preprocessor)/config/filter.param.yaml"/>
8+
<node pkg="autoware_pointcloud_preprocessor" exec="pointcloud_accumulator_node" name="pointcloud_accumulator_node">
9+
<param from="$(var pointcloud_accumulator_param_file)"/>
10+
<param from="$(var filter_param_file)"/>
11+
<remap from="input" to="$(var input_topic_name)"/>
12+
<remap from="output" to="$(var output_topic_name)"/>
13+
<param name="input_frame" value="$(var input_frame)"/>
14+
<param name="output_frame" value="$(var output_frame)"/>
15+
</node>
16+
</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 Pointcloud Accumulator Node",
4+
"type": "object",
5+
"definitions": {
6+
"pointcloud_accumulator": {
7+
"type": "object",
8+
"properties": {
9+
"accumulation_time_sec": {
10+
"type": "number",
11+
"description": "accumulation period [s]",
12+
"default": "2.0",
13+
"minimum": 0
14+
},
15+
"pointcloud_buffer_size": {
16+
"type": "integer",
17+
"description": "buffer size",
18+
"default": "50",
19+
"minimum": 0
20+
}
21+
},
22+
"required": ["accumulation_time_sec", "pointcloud_buffer_size"],
23+
"additionalProperties": false
24+
}
25+
},
26+
"properties": {
27+
"/**": {
28+
"type": "object",
29+
"properties": {
30+
"ros__parameters": {
31+
"$ref": "#/definitions/pointcloud_accumulator"
32+
}
33+
},
34+
"required": ["ros__parameters"],
35+
"additionalProperties": false
36+
}
37+
},
38+
"required": ["/**"],
39+
"additionalProperties": false
40+
}

sensing/autoware_pointcloud_preprocessor/src/pointcloud_accumulator/pointcloud_accumulator_nodelet.cpp renamed to sensing/autoware_pointcloud_preprocessor/src/pointcloud_accumulator/pointcloud_accumulator_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/pointcloud_accumulator/pointcloud_accumulator_nodelet.hpp"
15+
#include "autoware/pointcloud_preprocessor/pointcloud_accumulator/pointcloud_accumulator_node.hpp"
1616

1717
#include <vector>
1818

@@ -23,9 +23,9 @@ PointcloudAccumulatorComponent::PointcloudAccumulatorComponent(const rclcpp::Nod
2323
{
2424
// set initial parameters
2525
{
26-
accumulation_time_sec_ = static_cast<double>(declare_parameter("accumulation_time_sec", 2.0));
26+
accumulation_time_sec_ = declare_parameter<double>("accumulation_time_sec");
2727
pointcloud_buffer_.set_capacity(
28-
static_cast<size_t>(declare_parameter("pointcloud_buffer_size", 50)));
28+
static_cast<size_t>(declare_parameter<int64_t>("pointcloud_buffer_size")));
2929
}
3030

3131
using std::placeholders::_1;

0 commit comments

Comments
 (0)