Skip to content

Commit 2077fae

Browse files
badai-nguyenmanatopre-commit-ci[bot]yukkysaitokminoda
authored
feat: cherry-pick and add image_segmentation_based_filter for beta/v0.29.0 (#1526)
* feat(tensorrt yolox): inference and publish mask image from yolox model with semantic segmentation header (autowarefoundation#5553) * add segmentation model Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> fix: add multitask for segment Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: publish mask Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * feat: publish colorized mask Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: resize yolox mask Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: add memory allocate operations Signed-off-by: Manato HIRABAYASHI <manato.hirabayashi@tier4.jp> * refactor: remove underscore for a local variable Signed-off-by: Manato HIRABAYASHI <manato.hirabayashi@tier4.jp> * chore: add condition to check the number of subscriber for newly added topics Signed-off-by: Manato HIRABAYASHI <manato.hirabayashi@tier4.jp> * chore: pre-commit Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: add roi overlapping segment Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: roi overlay segment Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * chore: refactor Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * docs: update readme Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: update model name Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: add utils into tensorrt_yolox Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: launch file Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * chore: remove unnecessary depend Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * chore: fix yaml file Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * chore: remove duplicated param in launch Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: semantic class Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * docs: update readme Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * chore: update default param Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: add processing time topic Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * chore: typo Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * style(pre-commit): autofix * chore: fix cspell error Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: yolox default param Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * chore: rename debug topics Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * chore: rename debug topics Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * docs: update model description Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * style(pre-commit): autofix * fix: launch Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * refactor: unpublish mask for single task Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * Update perception/tensorrt_yolox/src/tensorrt_yolox.cpp Co-authored-by: Manato Hirabayashi <3022416+manato@users.noreply.github.com> * Update perception/tensorrt_yolox/src/tensorrt_yolox.cpp Co-authored-by: Manato Hirabayashi <3022416+manato@users.noreply.github.com> * Update perception/tensorrt_yolox/src/tensorrt_yolox.cpp Co-authored-by: Manato Hirabayashi <3022416+manato@users.noreply.github.com> * style(pre-commit): autofix * docs: update reamde Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * style(pre-commit): autofix * fix: skip mask size as yolox output Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> --------- Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> Signed-off-by: Manato HIRABAYASHI <manato.hirabayashi@tier4.jp> Co-authored-by: Manato HIRABAYASHI <manato.hirabayashi@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Manato Hirabayashi <3022416+manato@users.noreply.github.com> * fix(tensorrt_yolox): add run length encoding for sematic segmentation mask (autowarefoundation#7905) * fix: add rle compress Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: rle compress Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: move rle into utils Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * chore: pre-commit Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * Update perception/autoware_tensorrt_yolox/src/utils.cpp Co-authored-by: Yukihiro Saito <yukky.saito@gmail.com> * fix: remove unused variable Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * Update perception/autoware_tensorrt_yolox/src/utils.cpp Co-authored-by: Manato Hirabayashi <3022416+manato@users.noreply.github.com> * style(pre-commit): autofix * feat: add unit test for utils Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * style(pre-commit): autofix * fix: unit test Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * chore: change to explicit index Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * style(pre-commit): autofix * fix: cuda cmake Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: separate unit test into different PR Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> --------- Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> Co-authored-by: Yukihiro Saito <yukky.saito@gmail.com> Co-authored-by: Manato Hirabayashi <3022416+manato@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * refactor(tensorrt_yolox): move utils into perception_utils (autowarefoundation#8435) * chore(tensorrt_yolo): refactor utils Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * style(pre-commit): autofix * fix: tensorrt_yolox Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> --------- Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> * fix(perception_utils): install library after build (autowarefoundation#8501) Signed-off-by: Manato HIRABAYASHI <manato.hirabayashi@tier4.jp> * fix(image_projection_based_fusion): resize sematic segmentation mask as input image size (autowarefoundation#7635) Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix(image_projection_based_fusion): segmentation pointcloud fusion param update (autowarefoundation#7858) * fix(image_projection_based_fusion): add run length decoding for segmentation_pointcloud_fusion (autowarefoundation#7909) * fix: add rle decompress Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * style(pre-commit): autofix * fix: use rld in tensorrt utils Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: rebase error Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: dependency Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: skip publish debug mask Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * Update perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> * style(pre-commit): autofix * Revert "fix: skip publish debug mask" This reverts commit 30fa9ae. --------- Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> * feat(tier4_perception_launch): add image segmentation based pointcloud filter (autowarefoundation#7225) * feat(tier4_perception_launch): add image segmentation based pointcloud filter Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * chore: typo Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * fix: detection launch Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * chore: add maintainer Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * Revert "chore: add maintainer" This reverts commit 5adfef6. --------- Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> * style(pre-commit): autofix * fix(autoware_image_projection_based_fusion): resolve issue with segmentation pointcloud fusion node failing with multiple mask inputs (autowarefoundation#8769) --------- Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp> Signed-off-by: Manato HIRABAYASHI <manato.hirabayashi@tier4.jp> Co-authored-by: Manato HIRABAYASHI <manato.hirabayashi@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: Manato Hirabayashi <3022416+manato@users.noreply.github.com> Co-authored-by: Yukihiro Saito <yukky.saito@gmail.com> Co-authored-by: kminoda <44218668+kminoda@users.noreply.github.com> Co-authored-by: Yi-Hsiang Fang (Vivid) <146902905+vividf@users.noreply.github.com>
1 parent 79dc610 commit 2077fae

File tree

25 files changed

+976
-117
lines changed

25 files changed

+976
-117
lines changed

common/perception_utils/CMakeLists.txt

+9
Original file line numberDiff line numberDiff line change
@@ -4,4 +4,13 @@ project(perception_utils)
44
find_package(autoware_cmake REQUIRED)
55
autoware_package()
66

7+
ament_auto_add_library(${PROJECT_NAME} SHARED
8+
src/run_length_encoder.cpp
9+
)
10+
11+
find_package(OpenCV REQUIRED)
12+
target_link_libraries(${PROJECT_NAME}
13+
${OpenCV_LIBS}
14+
)
15+
716
ament_auto_package()
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,29 @@
1+
// Copyright 2024 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef PERCEPTION_UTILS__RUN_LENGTH_ENCODER_HPP_
16+
17+
#define PERCEPTION_UTILS__RUN_LENGTH_ENCODER_HPP_
18+
#include <opencv2/opencv.hpp>
19+
20+
#include <utility>
21+
#include <vector>
22+
23+
namespace perception_utils
24+
{
25+
std::vector<std::pair<uint8_t, int>> runLengthEncoder(const cv::Mat & mask);
26+
cv::Mat runLengthDecoder(const std::vector<uint8_t> & rle_data, const int rows, const int cols);
27+
} // namespace perception_utils
28+
29+
#endif // PERCEPTION_UTILS__RUN_LENGTH_ENCODER_HPP_

common/perception_utils/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212
<buildtool_depend>ament_cmake_auto</buildtool_depend>
1313
<buildtool_depend>autoware_cmake</buildtool_depend>
1414

15+
<depend>libopencv-dev</depend>
1516
<depend>rclcpp</depend>
1617

1718
<export>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,65 @@
1+
// Copyright 2024 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include "perception_utils/run_length_encoder.hpp"
16+
17+
namespace perception_utils
18+
{
19+
20+
std::vector<std::pair<uint8_t, int>> runLengthEncoder(const cv::Mat & image)
21+
{
22+
std::vector<std::pair<uint8_t, int>> compressed_data;
23+
const int rows = image.rows;
24+
const int cols = image.cols;
25+
compressed_data.emplace_back(image.at<uint8_t>(0, 0), 0);
26+
for (int i = 0; i < rows; ++i) {
27+
for (int j = 0; j < cols; ++j) {
28+
uint8_t current_value = image.at<uint8_t>(i, j);
29+
if (compressed_data.back().first == current_value) {
30+
++compressed_data.back().second;
31+
} else {
32+
compressed_data.emplace_back(current_value, 1);
33+
}
34+
}
35+
}
36+
return compressed_data;
37+
}
38+
39+
cv::Mat runLengthDecoder(const std::vector<uint8_t> & rle_data, const int rows, const int cols)
40+
{
41+
cv::Mat mask(rows, cols, CV_8UC1, cv::Scalar(0));
42+
int idx = 0;
43+
int step = sizeof(uint8_t) + sizeof(int);
44+
for (size_t i = 0; i < rle_data.size(); i += step) {
45+
uint8_t value;
46+
int length;
47+
std::memcpy(&value, &rle_data[i], sizeof(uint8_t));
48+
std::memcpy(
49+
&length, &rle_data[i + 1],
50+
sizeof(
51+
int)); // under the condition that we know rle_data[i] only consume 1 element of the vector
52+
for (int j = 0; j < length; ++j) {
53+
int row_idx = static_cast<int>(idx / cols);
54+
int col_idx = static_cast<int>(idx % cols);
55+
mask.at<uint8_t>(row_idx, col_idx) = value;
56+
idx++;
57+
if (idx > rows * cols) {
58+
break;
59+
}
60+
}
61+
}
62+
return mask;
63+
}
64+
65+
} // namespace perception_utils

common/tensorrt_common/include/tensorrt_common/tensorrt_common.hpp

+4
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,9 @@
1515
#ifndef TENSORRT_COMMON__TENSORRT_COMMON_HPP_
1616
#define TENSORRT_COMMON__TENSORRT_COMMON_HPP_
1717

18+
#ifndef YOLOX_STANDALONE
1819
#include <rclcpp/rclcpp.hpp>
20+
#endif
1921

2022
#include <NvInfer.h>
2123
#include <NvOnnxParser.h>
@@ -86,6 +88,7 @@ struct BuildConfig
8688
profile_per_layer(profile_per_layer),
8789
clip_value(clip_value)
8890
{
91+
#ifndef YOLOX_STANDALONE
8992
if (
9093
std::find(valid_calib_type.begin(), valid_calib_type.end(), calib_type_str) ==
9194
valid_calib_type.end()) {
@@ -95,6 +98,7 @@ struct BuildConfig
9598
<< "Default calibration type will be used: MinMax" << std::endl;
9699
std::cerr << message.str();
97100
}
101+
#endif
98102
}
99103
};
100104

launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml

+2
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@
33
<!-- Interface parameters -->
44
<arg name="mode" default="lidar" description="options: `camera_lidar_radar_fusion`, `camera_lidar_fusion`, `lidar_radar_fusion`, `lidar` or `radar`"/>
55
<arg name="use_detection_by_tracker"/>
6+
<arg name="use_image_segmentation_based_filter"/>
67

78
<!-- Lidar parameters -->
89
<arg name="input/pointcloud"/>
@@ -60,6 +61,7 @@
6061
<arg name="use_low_height_cropbox" value="$(var use_low_height_cropbox)"/>
6162
<arg name="use_roi_based_cluster" value="$(var use_roi_based_cluster)"/>
6263
<arg name="detection_by_tracker_param_path" value="$(var detection_by_tracker_param_path)"/>
64+
<arg name="use_image_segmentation_based_filter" value="$(var use_image_segmentation_based_filter)"/>
6365
</include>
6466
<!-- Lidar dnn-based detectors-->
6567
<include file="$(find-pkg-share tier4_perception_launch)/launch/object_recognition/detection/detector/lidar_dnn_detector.launch.xml">

launch/tier4_perception_launch/launch/object_recognition/detection/detector/camera_lidar_detector.launch.xml

+12-1
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99
<arg name="lidar_detection_model" default="centerpoint" description="options: `centerpoint`, `apollo`, `pointpainting`, `clustering`"/>
1010
<arg name="use_roi_based_cluster" default="false"/>
1111
<arg name="use_low_intensity_cluster_filter" default="false"/>
12+
<arg name="use_image_segmentation_based_filter" default="false"/>
1213

1314
<!-- Camera parameters -->
1415
<arg name="image_raw0" default="/image_raw" description="image raw topic name"/>
@@ -104,14 +105,24 @@
104105
</include>
105106
</group>
106107

108+
<!-- Image_segmentation based filter, apply for camera0 only-->
109+
<group>
110+
<include file="$(find-pkg-share image_projection_based_fusion)/launch/segmentation_pointcloud_fusion.launch.xml" if="$(var use_image_segmentation_based_filter)">
111+
<arg name="input/pointcloud" value="/perception/object_recognition/detection/pointcloud_map_filtered/pointcloud"/>
112+
<arg name="output/pointcloud" value="/perception/object_recognition/detection/segmentation_based_filtered/pointcloud"/>
113+
</include>
114+
</group>
115+
107116
<!-- Clustering -->
108117
<group>
109118
<push-ros-namespace namespace="clustering"/>
110119
<group>
120+
<let name="euclidean_cluster_input" value="/perception/object_recognition/detection/pointcloud_map_filtered/pointcloud" unless="$(var use_image_segmentation_based_filter)"/>
121+
<let name="euclidean_cluster_input" value="/perception/object_recognition/detection/segmentation_based_filtered/pointcloud" if="$(var use_image_segmentation_based_filter)"/>
111122
<let name="euclidean_cluster_output" value="euclidean_cluster/clusters" if="$(var use_roi_based_cluster)"/>
112123
<let name="euclidean_cluster_output" value="clusters" unless="$(var use_roi_based_cluster)"/>
113124
<include file="$(find-pkg-share euclidean_cluster)/launch/voxel_grid_based_euclidean_cluster.launch.xml">
114-
<arg name="input_pointcloud" value="/perception/object_recognition/detection/pointcloud_map_filtered/pointcloud"/>
125+
<arg name="input_pointcloud" value="$(var euclidean_cluster_input)"/>
115126
<arg name="output_clusters" value="$(var euclidean_cluster_output)"/>
116127
<arg name="use_low_height_cropbox" value="$(var use_low_height_cropbox)"/>
117128
</include>

launch/tier4_perception_launch/launch/perception.launch.xml

+2
Original file line numberDiff line numberDiff line change
@@ -79,6 +79,7 @@
7979
<arg name="use_object_filter" default="true" description="use object filter"/>
8080
<arg name="use_roi_based_cluster" default="true" description="use roi_based_cluster in clustering"/>
8181
<arg name="use_low_intensity_cluster_filter" default="true" description="use low_intensity_cluster_filter in clustering"/>
82+
<arg name="use_image_segmentation_based_filter" default="true" description="use image_segmentation_based_filter in clustering"/>
8283
<arg
8384
name="use_empty_dynamic_object_publisher"
8485
default="false"
@@ -221,6 +222,7 @@
221222
<arg name="use_radar_tracking_fusion" value="$(var use_radar_tracking_fusion)"/>
222223
<arg name="use_pointcloud_map" value="$(var use_pointcloud_map)"/>
223224
<arg name="use_low_height_cropbox" value="$(var use_low_height_cropbox)"/>
225+
<arg name="use_image_segmentation_based_filter" value="$(var use_image_segmentation_based_filter)"/>
224226
<arg name="use_object_filter" value="$(var use_object_filter)"/>
225227
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
226228
<arg name="use_roi_based_cluster" value="$(var use_roi_based_cluster)"/>
Original file line numberDiff line numberDiff line change
@@ -1,39 +1,27 @@
11
/**:
22
ros__parameters:
33
# if the semantic label is applied for pointcloud filtering
4+
45
filter_semantic_label_target:
5-
[
6-
true, # road
7-
true, # sidewalk
8-
true, # building
9-
true, # wall
10-
true, # fence
11-
true, # pole
12-
true, # traffic_light
13-
true, # traffic_sign
14-
true, # vegetation
15-
true, # terrain
16-
true, # sky
17-
false, # person
18-
false, # ride
19-
false, # car
20-
false, # truck
21-
false, # bus
22-
false, # train
23-
false, # motorcycle
24-
false, # bicycle
25-
false, # others
26-
]
27-
# the maximum distance of pointcloud to be applied filter,
28-
# this is selected based on semantic segmentation model accuracy,
29-
# calibration accuracy and unknown reaction distance
6+
UNKNOWN: false
7+
BUILDING: true
8+
WALL: true
9+
OBSTACLE: false
10+
TRAFFIC_LIGHT: false
11+
TRAFFIC_SIGN: false
12+
PERSON: false
13+
VEHICLE: false
14+
BIKE: false
15+
ROAD: true
16+
SIDEWALK: false
17+
ROAD_PAINT: false
18+
CURBSTONE: false
19+
CROSSWALK: false
20+
VEGETATION: true
21+
SKY: false
22+
23+
# the maximum distance of pointcloud to be applied filter
3024
filter_distance_threshold: 60.0
3125

32-
# debug
33-
debug_mode: false
34-
filter_scope_min_x: -100.0
35-
filter_scope_max_x: 100.0
36-
filter_scope_min_y: -100.0
37-
filter_scope_max_y: 100.0
38-
filter_scope_min_z: -100.0
39-
filter_scope_max_z: 100.0
26+
# Avoid using debug mask in case of multiple camera semantic segmentation fusion
27+
is_publish_debug_mask: false

perception/image_projection_based_fusion/docs/segmentation-pointcloud-fusion.md

+1-3
Original file line numberDiff line numberDiff line change
@@ -32,9 +32,7 @@ The node `segmentation_pointcloud_fusion` is a package for filtering pointcloud
3232

3333
### Core Parameters
3434

35-
| Name | Type | Description |
36-
| ------------- | ---- | ------------------------ |
37-
| `rois_number` | int | the number of input rois |
35+
{{ json_to_markdown("perception/image_projection_based_fusion/schema/segmentation_pointcloud_fusion.schema.json") }}
3836

3937
## Assumptions / Known limits
4038

perception/image_projection_based_fusion/include/image_projection_based_fusion/segmentation_pointcloud_fusion/node.hpp

+15-1
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,11 @@
1717

1818
#include "image_projection_based_fusion/fusion_node.hpp"
1919

20+
#include <image_transport/image_transport.hpp>
21+
2022
#include <string>
23+
#include <unordered_set>
24+
#include <utility>
2125
#include <vector>
2226

2327
#if __has_include(<cv_bridge/cv_bridge.hpp>)
@@ -34,7 +38,17 @@ class SegmentPointCloudFusionNode : public FusionNode<PointCloud2, PointCloud2,
3438
rclcpp::Publisher<PointCloud2>::SharedPtr pub_pointcloud_ptr_;
3539
std::vector<bool> filter_semantic_label_target_;
3640
float filter_distance_threshold_;
37-
/* data */
41+
// declare list of semantic label target, depend on trained data of yolox segmentation model
42+
std::vector<std::pair<std::string, bool>> filter_semantic_label_target_list_ = {
43+
{"UNKNOWN", false}, {"BUILDING", false}, {"WALL", false}, {"OBSTACLE", false},
44+
{"TRAFFIC_LIGHT", false}, {"TRAFFIC_SIGN", false}, {"PERSON", false}, {"VEHICLE", false},
45+
{"BIKE", false}, {"ROAD", false}, {"SIDEWALK", false}, {"ROAD_PAINT", false},
46+
{"CURBSTONE", false}, {"CROSSWALK", false}, {"VEGETATION", false}, {"SKY", false}};
47+
48+
image_transport::Publisher pub_debug_mask_ptr_;
49+
bool is_publish_debug_mask_;
50+
std::unordered_set<size_t> filter_global_offset_set_;
51+
3852
public:
3953
explicit SegmentPointCloudFusionNode(const rclcpp::NodeOptions & options);
4054

perception/image_projection_based_fusion/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@
2727
<depend>object_recognition_utils</depend>
2828
<depend>pcl_conversions</depend>
2929
<depend>pcl_ros</depend>
30+
<depend>perception_utils</depend>
3031
<depend>rclcpp</depend>
3132
<depend>rclcpp_components</depend>
3233
<depend>sensor_msgs</depend>

0 commit comments

Comments
 (0)