Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(autoware_pointcloud_preprocessor): rework blockage diag parameters #8488

Merged
Show file tree
Hide file tree
Changes from 3 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion sensing/autoware_pointcloud_preprocessor/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED
src/vector_map_filter/lanelet2_map_filter_nodelet.cpp
src/distortion_corrector/distortion_corrector.cpp
src/distortion_corrector/distortion_corrector_node.cpp
src/blockage_diag/blockage_diag_nodelet.cpp
src/blockage_diag/blockage_diag_node.cpp
src/polygon_remover/polygon_remover.cpp
src/vector_map_filter/vector_map_inside_area_filter.cpp
src/utility/geometry.cpp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,3 +14,7 @@
max_distance_range: 200.0
horizontal_resolution: 0.4
blockage_kernel: 10
angle_range: [0.0, 360.0]
vertical_bins: 40
is_channel_order_top2down: true
horizontal_ring_id: 18
19 changes: 1 addition & 18 deletions sensing/autoware_pointcloud_preprocessor/docs/blockage_diag.md
Original file line number Diff line number Diff line change
Expand Up @@ -51,24 +51,7 @@ This implementation inherits `autoware::pointcloud_preprocessor::Filter` class,

## Parameters

| Name | Type | Description |
| ----------------------------- | ------ | ----------------------------------------------------------------------------------------------------------------------------- |
| `blockage_ratio_threshold` | float | The threshold of blockage area ratio.If the blockage value exceeds this threshold, the diagnostic state will be set to ERROR. |
| `blockage_count_threshold` | float | The threshold of number continuous blockage frames |
| `horizontal_ring_id` | int | The id of horizontal ring of the LiDAR |
| `angle_range` | vector | The effective range of LiDAR |
| `vertical_bins` | int | The LiDAR channel number |
| `is_channel_order_top2down` | bool | If the lidar channels are indexed from top to down |
| `blockage_buffering_frames` | int | The number of buffering about blockage detection [range:1-200] |
| `blockage_buffering_interval` | int | The interval of buffering about blockage detection |
| `dust_ratio_threshold` | float | The threshold of dusty area ratio |
| `dust_count_threshold` | int | The threshold of number continuous frames include dusty area |
| `blockage_kernel` | int | The kernel size of morphology processing the detected blockage area |
| `dust_kernel_size` | int | The kernel size of morphology processing in dusty area detection |
| `dust_buffering_frames` | int | The number of buffering about dusty area detection [range:1-200] |
| `dust_buffering_interval` | int | The interval of buffering about dusty area detection |
| `max_distance_range` | double | Maximum view range for the LiDAR |
| `horizontal_resolution` | double | The horizontal resolution of depth map image [deg/pixel] |
{{ json_to_markdown("sensing/autoware_pointcloud_preprocessor/schema/blockage_diag_node.schema.json") }}

## Assumptions / Known limits

Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2022 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__BLOCKAGE_DIAG__BLOCKAGE_DIAG_NODELET_HPP_
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__BLOCKAGE_DIAG__BLOCKAGE_DIAG_NODELET_HPP_
#ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__BLOCKAGE_DIAG__BLOCKAGE_DIAG_NODE_HPP_
#define AUTOWARE__POINTCLOUD_PREPROCESSOR__BLOCKAGE_DIAG__BLOCKAGE_DIAG_NODE_HPP_

#include "autoware/pointcloud_preprocessor/filter.hpp"

Expand Down Expand Up @@ -105,4 +105,4 @@ class BlockageDiagComponent : public autoware::pointcloud_preprocessor::Filter

} // namespace autoware::pointcloud_preprocessor

#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__BLOCKAGE_DIAG__BLOCKAGE_DIAG_NODELET_HPP_
#endif // AUTOWARE__POINTCLOUD_PREPROCESSOR__BLOCKAGE_DIAG__BLOCKAGE_DIAG_NODE_HPP_

This file was deleted.

Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
<launch>
<arg name="input_topic_name" default="pointcloud_raw_ex"/>
<arg name="output_topic_name" default="blockage_diag/pointcloud"/>
<arg name="blockage_diagnostics_param_file" default="$(find-pkg-share autoware_pointcloud_preprocessor)/config/blockage_diag_node.param.yaml"/>
<node pkg="autoware_pointcloud_preprocessor" exec="blockage_diag_node" name="blockage_diag_node">
<remap from="input" to="$(var input_topic_name)"/>
<remap from="output" to="$(var output_topic_name)"/>
<param from="$(var blockage_diagnostics_param_file)"/>
</node>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,143 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for Blockage Diag Node",
"type": "object",
"definitions": {
"blockage_diag": {
"type": "object",
"properties": {
"blockage_ratio_threshold": {
"type": "number",
"description": "The threshold of blockage area ratio.If the blockage value exceeds this threshold, the diagnostic state will be set to ERROR.",
"default": "0.1"
},
"blockage_count_threshold": {
"type": "number",
"description": "The threshold of number continuous blockage frames",
"default": "50"
},
"blockage_buffering_frames": {
"type": "integer",
"description": "The number of buffering about blockage detection [range:1-200]",
"default": "2"
},
"blockage_buffering_interval": {
"type": "integer",
"description": "The interval of buffering about blockage detection",
"default": "1"
},
"enable_dust_diag": {
"type": "boolean",
"description": "enable dust diagnostic",
"default": "false"
},
"publish_debug_image": {
"type": "boolean",
"description": "publish debug image",
"default": "false"
},
"dust_ratio_threshold": {
"type": "number",
"description": "The threshold of dusty area ratio",
"default": "0.2"
},
"dust_count_threshold": {
"type": "integer",
"description": "The threshold of number continuous frames include dusty area",
"default": "10"
},
"dust_kernel_size": {
"type": "integer",
"description": "The kernel size of morphology processing in dusty area detection",
"default": "2"
},
"dust_buffering_frames": {
"type": "integer",
"description": "The number of buffering about dusty area detection [range:1-200]",
"default": "10"
},
"dust_buffering_interval": {
"type": "integer",
"description": "The interval of buffering about dusty area detection",
"default": "1"
},
"max_distance_range": {
"type": "number",
"description": "Maximum view range for the LiDAR",
"default": "200.0"
},
"horizontal_resolution": {
"type": "number",
"description": "The horizontal resolution of depth map image [deg/pixel]",
"default": "0.4"
},
"blockage_kernel": {
"type": "integer",
"description": "The kernel size of morphology processing the detected blockage area",
"default": "10"
},
"angle_range": {
"type": "array",
"description": "The effective range of LiDAR",
"minItems": 2,
"maxItems": 2,
"items": {
"type": "number",
"minimum": 0.0,
"maximum": 360.0
}
},
"vertical_bins": {
"type": "integer",
"description": "The LiDAR channel",
"default": "40"
},
"is_channel_order_top2down": {
"type": "boolean",
"description": "If the lidar channels are indexed from top to down",
"default": "true"
},
"horizontal_ring_id": {
"type": "integer",
"description": "The id of horizontal ring of the LiDAR",
"default": "18"
}
},
"required": [
"blockage_ratio_threshold",
"blockage_count_threshold",
"blockage_buffering_frames",
"blockage_buffering_interval",
"enable_dust_diag",
"publish_debug_image",
"dust_ratio_threshold",
"dust_count_threshold",
"dust_kernel_size",
"dust_buffering_frames",
"dust_buffering_interval",
"max_distance_range",
"horizontal_resolution",
"blockage_kernel",
"angle_range",
"vertical_bins",
"is_channel_order_top2down",
"horizontal_ring_id"
],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/blockage_diag"
}
},
"required": ["ros__parameters"],
"additionalProperties": false
}
},
"required": ["/**"],
"additionalProperties": false
}
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2022 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/blockage_diag/blockage_diag_nodelet.hpp"
#include "autoware/pointcloud_preprocessor/blockage_diag/blockage_diag_node.hpp"

#include "autoware_point_types/types.hpp"

Expand Down
Loading