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

feat: add blockage diagnostics #461

Merged
merged 26 commits into from
Mar 28, 2022
Merged
Show file tree
Hide file tree
Changes from 24 commits
Commits
Show all changes
26 commits
Select commit Hold shift + click to select a range
ba310c1
feat!: add blockage diagnostic
badai-nguyen Feb 25, 2022
a5c7b91
fix: typo
badai-nguyen Feb 28, 2022
52bf4df
docs: add documentation
badai-nguyen Mar 1, 2022
22ddbc0
ci(pre-commit): autofix
pre-commit-ci[bot] Mar 2, 2022
e8197ed
fix: typo
badai-nguyen Mar 2, 2022
bd37bdb
ci(pre-commit): autofix
pre-commit-ci[bot] Mar 2, 2022
4da7a01
fix: typo
badai-nguyen Mar 9, 2022
b6021ca
chore: add adjustable param
badai-nguyen Mar 10, 2022
fe38852
ci(pre-commit): autofix
pre-commit-ci[bot] Mar 10, 2022
c5d6a91
feat!: add blockage diagnostic
badai-nguyen Feb 25, 2022
d9d3b1b
fix: typo
badai-nguyen Feb 28, 2022
97992b2
docs: add documentation
badai-nguyen Mar 1, 2022
3a8e45c
ci(pre-commit): autofix
pre-commit-ci[bot] Mar 2, 2022
ace75ef
fix: typo
badai-nguyen Mar 2, 2022
ff46e7e
ci(pre-commit): autofix
pre-commit-ci[bot] Mar 2, 2022
6daf9f9
fix: typo
badai-nguyen Mar 9, 2022
7348731
chore: add adjustable param
badai-nguyen Mar 10, 2022
0f1acd7
ci(pre-commit): autofix
pre-commit-ci[bot] Mar 10, 2022
61c77fe
Merge branch 'blockage_v0.1' of github.com:badai-nguyen/autoware.univ…
badai-nguyen Mar 10, 2022
0bff5c3
chore: rearrange header file
badai-nguyen Mar 16, 2022
a7ce3f1
chore: fix typo
badai-nguyen Mar 24, 2022
c983517
chore: rearrange header
badai-nguyen Mar 25, 2022
5126d67
fix: revert accident change
badai-nguyen Mar 27, 2022
a588b27
chore: fix typo
badai-nguyen Mar 28, 2022
9cfcee2
docs: add limits
badai-nguyen Mar 28, 2022
f33e104
chore: check overflow
badai-nguyen Mar 28, 2022
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
6 changes: 6 additions & 0 deletions common/autoware_point_types/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,12 @@ endif()
find_package(ament_cmake_auto REQUIRED)
ament_auto_find_build_dependencies()

include_directories(
include
SYSTEM
${PCL_INCLUDE_DIRS}
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@

#include <point_cloud_msg_wrapper/point_cloud_msg_wrapper.hpp>

#include <pcl/point_types.h>

#include <cmath>
#include <tuple>

Expand All @@ -41,6 +43,17 @@ struct PointXYZI
}
};

enum ReturnType : uint8_t {
INVALID = 0,
SINGLE_STRONGEST,
SINGLE_LAST,
DUAL_STRONGEST_FIRST,
DUAL_STRONGEST_LAST,
DUAL_WEAK_FIRST,
DUAL_WEAK_LAST,
DUAL_ONLY,
};

struct PointXYZIRADRT
{
float x{0.0F};
Expand Down Expand Up @@ -77,4 +90,10 @@ using PointXYZIRADRTGenerator = std::tuple<

} // namespace autoware_point_types

POINT_CLOUD_REGISTER_POINT_STRUCT(
autoware_point_types::PointXYZIRADRT,
(float, x, x)(float, y, y)(float, z, z)(float, intensity, intensity)(std::uint16_t, ring, ring)(
float, azimuth, azimuth)(float, distance, distance)(std::uint8_t, return_type, return_type)(
double, time_stamp, time_stamp))

#endif // AUTOWARE_POINT_TYPES__TYPES_HPP_
1 change: 1 addition & 0 deletions common/autoware_point_types/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
<depend>ament_cmake_cppcheck</depend>
<depend>ament_cmake_lint_cmake</depend>
<depend>ament_cmake_xmllint</depend>
<depend>pcl_ros</depend>
<depend>point_cloud_msg_wrapper</depend>

<test_depend>ament_cmake_gtest</test_depend>
Expand Down
5 changes: 5 additions & 0 deletions sensing/pointcloud_preprocessor/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@ ament_auto_add_library(pointcloud_preprocessor_filter SHARED
src/pointcloud_accumulator/pointcloud_accumulator_nodelet.cpp
src/vector_map_filter/lanelet2_map_filter_nodelet.cpp
src/distortion_corrector/distortion_corrector.cpp
src/blockage_diag/blockage_diag_nodelet.cpp
)

target_link_libraries(pointcloud_preprocessor_filter
Expand Down Expand Up @@ -149,6 +150,10 @@ rclcpp_components_register_node(pointcloud_preprocessor_filter
PLUGIN "pointcloud_preprocessor::DistortionCorrectorComponent"
EXECUTABLE distortion_corrector_node)

# ========== Blockage Diagnostics ===========
rclcpp_components_register_node(pointcloud_preprocessor_filter
PLUGIN "pointcloud_preprocessor::BlockageDiagComponent"
EXECUTABLE blockage_diag_node)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
Expand Down
59 changes: 59 additions & 0 deletions sensing/pointcloud_preprocessor/docs/blockage_diag.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,59 @@
# blockage_diag

## Purpose

To ensure the performance of LiDAR and safety for autonomous driving, the abnormal condition diagnostics feature is needed.
LiDAR blockage is abnormal condition of LiDAR when some unwanted objects stitch to and block the light pulses and return signal.
This node's purpose is to detect the existing of blockage on LiDAR and its related size and location.

## Inner-workings / Algorithms

This node bases on the no-return region and its location to decide if it is a blockage.

![blockage situation](./image/blockage_diag.png)

The logic is showed as below

![blockage_diag_flowchart](./image/blockage_diag_flowchart.drawio.svg)

## Inputs / Outputs

This implementation inherits `pointcloud_preprocessor::Filter` class, please refer [README](../README.md).

### Input

| Name | Type | Description |
| --------------------------- | ------------------------------- | --------------------------------------------------------------- |
| `~/input/pointcloud_raw_ex` | `sensor_msgs::msg::PointCloud2` | The raw point cloud data is used to detect the no-return region |

### Output

| Name | Type | Description |
| ---------------------------------------------------- | --------------------------------------- | -------------------------------------------------- |
| `~/output/blockage_diag/debug/blockage_mask_image` | `sensor_msgs::msg::Image` | The mask image of detected blockage |
| `~/output/blockage_diag/debug/ground_blockage_ratio` | `tier4_debug_msgs::msg::Float32Stamped` | The area ratio of blockage region in ground region |
| `~/output/blockage_diag/debug/sky_blockage_ratio` | `tier4_debug_msgs::msg::Float32Stamped` | The area ratio of blockage region in sky region |
| `~/output/blockage_diag/debug/lidar_depth_map` | `sensor_msgs::msg::Image` | The depth map image of input point cloud |

## Parameters

| Name | Type | Description |
| -------------------------- | ------ | -------------------------------------------------- |
| `blockage_ratio_threshold` | float | The threshold of blockage area ratio |
| `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 |
| `model` | string | The LiDAR model |

miursh marked this conversation as resolved.
Show resolved Hide resolved
## Assumptions / Known limits

The current logic is still limited for dust type of blockage when dust particles are sparsely distributed.

miursh marked this conversation as resolved.
Show resolved Hide resolved
## (Optional) Error detection and handling

## (Optional) Performance characterization

## References/External links

## (Optional) Future extensions / Unimplemented parts
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ This node can remove rain and fog by considering the light reflected from the ob

![outlier_filter-return_type](./image/outlier_filter-return_type.drawio.svg)

Therefore, in order to use this node, the sensor driver must publish custom data including `return_type`. please refer to [PointXYZIRADT](https://github.com/tier4/AutowareArchitectureProposal.iv/blob/5d8dff0db51634f0c42d2a3e87ca423fbee84348/sensing/preprocessor/pointcloud/pointcloud_preprocessor/include/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_nodelet.hpp#L86-L96) data structure.
Therefore, in order to use this node, the sensor driver must publish custom data including `return_type`. please refer to [PointXYZIRADRT](../../../common/autoware_point_types/include/autoware_point_types/types.hpp#L57-L76) data structure.

Another feature of this node is that it publishes visibility as a diagnostic topic. With this function, for example, in heavy rain, the sensing module can notify that the processing performance has reached its limit, which can lead to ensuring the safety of the vehicle.

Expand Down Expand Up @@ -73,7 +73,7 @@ This implementation inherits `pointcloud_preprocessor::Filter` class, please ref
## Assumptions / Known limits

Not recommended for use as it is under development.
Input data must be `PointXYZIRADT` type data including `return_type`.
Input data must be `PointXYZIRADRT` type data including `return_type`.

## (Optional) Error detection and handling

Expand Down
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Original file line number Diff line number Diff line change
@@ -0,0 +1,80 @@
// Copyright 2022 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.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef POINTCLOUD_PREPROCESSOR__BLOCKAGE_DIAG__BLOCKAGE_DIAG_NODELET_HPP_
#define POINTCLOUD_PREPROCESSOR__BLOCKAGE_DIAG__BLOCKAGE_DIAG_NODELET_HPP_

#include "pointcloud_preprocessor/filter.hpp"

#include <diagnostic_updater/diagnostic_updater.hpp>
#include <image_transport/image_transport.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <rclcpp/rclcpp.hpp>

#include <diagnostic_msgs/msg/diagnostic_array.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <std_msgs/msg/header.hpp>
#include <tier4_debug_msgs/msg/float32_stamped.hpp>

#include <cv_bridge/cv_bridge.h>

#include <string>
#include <vector>

namespace pointcloud_preprocessor
{
using diagnostic_updater::DiagnosticStatusWrapper;
using diagnostic_updater::Updater;

class BlockageDiagComponent : public pointcloud_preprocessor::Filter
{
protected:
virtual void filter(
const PointCloud2ConstPtr & input, [[maybe_unused]] const IndicesPtr & indices,
PointCloud2 & output);
/** \brief Parameter service callback result : needed to be hold */
OnSetParametersCallbackHandle::SharedPtr set_param_res_;

/** \brief Parameter service callback */
rcl_interfaces::msg::SetParametersResult paramCallback(const std::vector<rclcpp::Parameter> & p);
image_transport::Publisher lidar_depth_map_pub_;
image_transport::Publisher blockage_mask_pub_;
rclcpp::Publisher<tier4_debug_msgs::msg::Float32Stamped>::SharedPtr ground_blockage_ratio_pub_;
rclcpp::Publisher<tier4_debug_msgs::msg::Float32Stamped>::SharedPtr sky_blockage_ratio_pub_;

private:
void onBlockageChecker(DiagnosticStatusWrapper & stat);
Updater updater_{this};
uint vertical_bins_;
std::vector<double> angle_range_deg_;
uint horizontal_ring_id_ = 12;
float blockage_ratio_threshold_;
float ground_blockage_ratio_ = -1.0f;
float sky_blockage_ratio_ = -1.0f;
std::vector<float> ground_blockage_range_deg_ = {0.0f, 0.0f};
std::vector<float> sky_blockage_range_deg_ = {0.0f, 0.0f};
uint erode_kernel_ = 10;
uint ground_blockage_count_ = 0;
uint sky_blockage_count_ = 0;
uint blockage_count_threshold_;
std::string lidar_model_;

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
explicit BlockageDiagComponent(const rclcpp::NodeOptions & options);
};

} // namespace pointcloud_preprocessor

#endif // POINTCLOUD_PREPROCESSOR__BLOCKAGE_DIAG__BLOCKAGE_DIAG_NODELET_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -39,17 +39,6 @@ namespace pointcloud_preprocessor
using diagnostic_updater::DiagnosticStatusWrapper;
using diagnostic_updater::Updater;

enum ReturnType : uint8_t {
INVALID = 0,
SINGLE_STRONGEST,
SINGLE_LAST,
DUAL_STRONGEST_FIRST,
DUAL_STRONGEST_LAST,
DUAL_WEAK_FIRST,
DUAL_WEAK_LAST,
DUAL_ONLY,
};

std::unordered_map<std::string, uint8_t> roi_mode_map_ = {
{"No_ROI", 0},
{"Fixed_xyz_ROI", 1},
Expand Down Expand Up @@ -101,26 +90,4 @@ class DualReturnOutlierFilterComponent : public pointcloud_preprocessor::Filter

} // namespace pointcloud_preprocessor

namespace return_type_cloud
{
struct PointXYZIRADT
{
PCL_ADD_POINT4D;
float intensity;
std::uint16_t ring;
float azimuth;
float distance;
std::uint8_t return_type;
double time_stamp;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
} EIGEN_ALIGN16;

} // namespace return_type_cloud

POINT_CLOUD_REGISTER_POINT_STRUCT(
return_type_cloud::PointXYZIRADT,
(float, x, x)(float, y, y)(float, z, z)(float, intensity, intensity)(std::uint16_t, ring, ring)(
float, azimuth, azimuth)(float, distance, distance)(std::uint8_t, return_type, return_type)(
double, time_stamp, time_stamp))

#endif // POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__DUAL_RETURN_OUTLIER_FILTER_NODELET_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
<launch>
<arg name="input_topic_name" default="pointcloud_raw_ex" />
<arg name="output_topic_name" default="blockage_diag/pointcloud" />

<node pkg="pointcloud_preprocessor" exec="blockage_diag_node" name="blockage_diag">
<remap from="input" to="$(var input_topic_name)" />
<remap from="output" to="$(var output_topic_name)" />
</node>
</launch>
Loading