Skip to content

Commit 8df7380

Browse files
badai-nguyenKhalilSelyan
authored and
KhalilSelyan
committed
fix(image_projection_based_fusion): segmentation pointcloud fusion param update (#7858)
1 parent 60ac4c8 commit 8df7380

File tree

5 files changed

+171
-42
lines changed

5 files changed

+171
-42
lines changed
Original file line numberDiff line numberDiff line change
@@ -1,39 +1,24 @@
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
30-
filter_distance_threshold: 60.0
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
3122

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
23+
# the maximum distance of pointcloud to be applied filter
24+
filter_distance_threshold: 60.0

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

+8-1
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
#include <image_projection_based_fusion/utils/utils.hpp>
2121

2222
#include <string>
23+
#include <utility>
2324
#include <vector>
2425

2526
#if __has_include(<cv_bridge/cv_bridge.hpp>)
@@ -36,7 +37,13 @@ class SegmentPointCloudFusionNode : public FusionNode<PointCloud2, PointCloud2,
3637
rclcpp::Publisher<PointCloud2>::SharedPtr pub_pointcloud_ptr_;
3738
std::vector<bool> filter_semantic_label_target_;
3839
float filter_distance_threshold_;
39-
/* data */
40+
// declare list of semantic label target, depend on trained data of yolox segmentation model
41+
std::vector<std::pair<std::string, bool>> filter_semantic_label_target_list_ = {
42+
{"UNKNOWN", false}, {"BUILDING", false}, {"WALL", false}, {"OBSTACLE", false},
43+
{"TRAFFIC_LIGHT", false}, {"TRAFFIC_SIGN", false}, {"PERSON", false}, {"VEHICLE", false},
44+
{"BIKE", false}, {"ROAD", false}, {"SIDEWALK", false}, {"ROAD_PAINT", false},
45+
{"CURBSTONE", false}, {"CROSSWALK", false}, {"VEGETATION", false}, {"SKY", false}};
46+
4047
public:
4148
explicit SegmentPointCloudFusionNode(const rclcpp::NodeOptions & options);
4249

Original file line numberDiff line numberDiff line change
@@ -0,0 +1,134 @@
1+
{
2+
"$schema": "http://json-schema.org/draft-07/schema#",
3+
"title": "Parameters for Segmentation Pointcloud Fusion Node",
4+
"type": "object",
5+
"definitions": {
6+
"segmentation_pointcloud_fusion": {
7+
"type": "object",
8+
"properties": {
9+
"filter_semantic_label_target": {
10+
"type": "object",
11+
"properties": {
12+
"UNKNOWN": {
13+
"type": "boolean",
14+
"description": "If true, UNKNOWN class of semantic will be filtered.",
15+
"default": false
16+
},
17+
"BUILDING": {
18+
"type": "boolean",
19+
"description": "If true, BUILDING class of semantic will be filtered.",
20+
"default": true
21+
},
22+
"WALL": {
23+
"type": "boolean",
24+
"description": "If true, WALL class of semantic will be filtered.",
25+
"default": true
26+
},
27+
"OBSTACLE": {
28+
"type": "boolean",
29+
"description": "If true, OBSTACLE class of semantic will be filtered.",
30+
"default": false
31+
},
32+
"TRAFFIC_LIGHT": {
33+
"type": "boolean",
34+
"description": "If true, TRAFFIC_LIGHT class of semantic will be filtered.",
35+
"default": false
36+
},
37+
"TRAFFIC_SIGN": {
38+
"type": "boolean",
39+
"description": "If true, TRAFFIC_SIGN class of semantic will be filtered.",
40+
"default": false
41+
},
42+
"PERSON": {
43+
"type": "boolean",
44+
"description": "If true, PERSON class of semantic will be filtered.",
45+
"default": false
46+
},
47+
"VEHICLE": {
48+
"type": "boolean",
49+
"description": "If true, VEHICLE class of semantic will be filtered.",
50+
"default": false
51+
},
52+
"BIKE": {
53+
"type": "boolean",
54+
"description": "If true, BIKE class of semantic will be filtered.",
55+
"default": false
56+
},
57+
"ROAD": {
58+
"type": "boolean",
59+
"description": "If true, ROAD class of semantic will be filtered.",
60+
"default": true
61+
},
62+
"SIDEWALK": {
63+
"type": "boolean",
64+
"description": "If true, SIDEWALK class of semantic will be filtered.",
65+
"default": false
66+
},
67+
"ROAD_PAINT": {
68+
"type": "boolean",
69+
"description": "If true, ROAD_PAINT class of semantic will be filtered.",
70+
"default": false
71+
},
72+
"CURBSTONE": {
73+
"type": "boolean",
74+
"description": "If true, CURBSTONE class of semantic will be filtered.",
75+
"default": false
76+
},
77+
"CROSSWALK": {
78+
"type": "boolean",
79+
"description": "If true, CROSSWALK class of semantic will be filtered.",
80+
"default": false
81+
},
82+
"VEGETATION": {
83+
"type": "boolean",
84+
"description": "If true, VEGETATION class of semantic will be filtered.",
85+
"default": true
86+
},
87+
"SKY": {
88+
"type": "boolean",
89+
"description": "If true, SKY class of semantic will be filtered.",
90+
"default": false
91+
}
92+
},
93+
"required": [
94+
"UNKNOWN",
95+
"BUILDING",
96+
"WALL",
97+
"OBSTACLE",
98+
"TRAFFIC_LIGHT",
99+
"TRAFFIC_SIGN",
100+
"PERSON",
101+
"VEHICLE",
102+
"BIKE",
103+
"ROAD",
104+
"SIDEWALK",
105+
"ROAD_PAINT",
106+
"CURBSTONE",
107+
"CROSSWALK",
108+
"VEGETATION",
109+
"SKY"
110+
]
111+
},
112+
"filter_distance_threshold": {
113+
"type": "number",
114+
"description": "A maximum distance of pointcloud to apply filter [m].",
115+
"default": 60.0,
116+
"minimum": 0.0
117+
}
118+
},
119+
"required": ["filter_semantic_label_target", "filter_distance_threshold"]
120+
}
121+
},
122+
"properties": {
123+
"/**": {
124+
"type": "object",
125+
"properties": {
126+
"ros__parameters": {
127+
"$ref": "#/definitions/segmentation_pointcloud_fusion"
128+
}
129+
},
130+
"required": ["ros__parameters"]
131+
}
132+
},
133+
"required": ["/**"]
134+
}

perception/image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp

+9-4
Original file line numberDiff line numberDiff line change
@@ -31,8 +31,13 @@ SegmentPointCloudFusionNode::SegmentPointCloudFusionNode(const rclcpp::NodeOptio
3131
: FusionNode<PointCloud2, PointCloud2, Image>("segmentation_pointcloud_fusion", options)
3232
{
3333
filter_distance_threshold_ = declare_parameter<float>("filter_distance_threshold");
34-
filter_semantic_label_target_ =
35-
declare_parameter<std::vector<bool>>("filter_semantic_label_target");
34+
for (auto & item : filter_semantic_label_target_list_) {
35+
item.second = declare_parameter<bool>("filter_semantic_label_target." + item.first);
36+
}
37+
for (const auto & item : filter_semantic_label_target_list_) {
38+
RCLCPP_INFO(
39+
this->get_logger(), "filter_semantic_label_target: %s %d", item.first.c_str(), item.second);
40+
}
3641
}
3742

3843
void SegmentPointCloudFusionNode::preprocess(__attribute__((unused)) PointCloud2 & pointcloud_msg)
@@ -129,12 +134,12 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage(
129134
// skip filtering pointcloud where semantic id out of the defined list
130135
uint8_t semantic_id = mask.at<uint8_t>(
131136
static_cast<uint16_t>(projected_point.y()), static_cast<uint16_t>(projected_point.x()));
132-
if (static_cast<size_t>(semantic_id) >= filter_semantic_label_target_.size()) {
137+
if (static_cast<size_t>(semantic_id) >= filter_semantic_label_target_list_.size()) {
133138
copyPointCloud(
134139
input_pointcloud_msg, point_step, global_offset, output_cloud, output_pointcloud_size);
135140
continue;
136141
}
137-
if (!filter_semantic_label_target_.at(semantic_id)) {
142+
if (!filter_semantic_label_target_list_.at(semantic_id).second) {
138143
copyPointCloud(
139144
input_pointcloud_msg, point_step, global_offset, output_cloud, output_pointcloud_size);
140145
}

0 commit comments

Comments
 (0)