Skip to content

Commit

Permalink
fix(image_projection_based_fusion): segmentation pointcloud fusion pa…
Browse files Browse the repository at this point in the history
…ram update (autowarefoundation#7858)
  • Loading branch information
badai-nguyen committed Sep 2, 2024
1 parent 088da15 commit 6afc0e0
Show file tree
Hide file tree
Showing 5 changed files with 171 additions and 42 deletions.
Original file line number Diff line number Diff line change
@@ -1,39 +1,24 @@
/**:
ros__parameters:
# if the semantic label is applied for pointcloud filtering

filter_semantic_label_target:
[
true, # road
true, # sidewalk
true, # building
true, # wall
true, # fence
true, # pole
true, # traffic_light
true, # traffic_sign
true, # vegetation
true, # terrain
true, # sky
false, # person
false, # ride
false, # car
false, # truck
false, # bus
false, # train
false, # motorcycle
false, # bicycle
false, # others
]
# the maximum distance of pointcloud to be applied filter,
# this is selected based on semantic segmentation model accuracy,
# calibration accuracy and unknown reaction distance
filter_distance_threshold: 60.0
UNKNOWN: false
BUILDING: true
WALL: true
OBSTACLE: false
TRAFFIC_LIGHT: false
TRAFFIC_SIGN: false
PERSON: false
VEHICLE: false
BIKE: false
ROAD: true
SIDEWALK: false
ROAD_PAINT: false
CURBSTONE: false
CROSSWALK: false
VEGETATION: true
SKY: false

# debug
debug_mode: false
filter_scope_min_x: -100.0
filter_scope_max_x: 100.0
filter_scope_min_y: -100.0
filter_scope_max_y: 100.0
filter_scope_min_z: -100.0
filter_scope_max_z: 100.0
# the maximum distance of pointcloud to be applied filter
filter_distance_threshold: 60.0
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,7 @@ The node `segmentation_pointcloud_fusion` is a package for filtering pointcloud

### Core Parameters

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

## Assumptions / Known limits

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include "image_projection_based_fusion/fusion_node.hpp"

#include <string>
#include <utility>
#include <vector>

#if __has_include(<cv_bridge/cv_bridge.hpp>)
Expand All @@ -34,7 +35,13 @@ class SegmentPointCloudFusionNode : public FusionNode<PointCloud2, PointCloud2,
rclcpp::Publisher<PointCloud2>::SharedPtr pub_pointcloud_ptr_;
std::vector<bool> filter_semantic_label_target_;
float filter_distance_threshold_;
/* data */
// declare list of semantic label target, depend on trained data of yolox segmentation model
std::vector<std::pair<std::string, bool>> filter_semantic_label_target_list_ = {
{"UNKNOWN", false}, {"BUILDING", false}, {"WALL", false}, {"OBSTACLE", false},
{"TRAFFIC_LIGHT", false}, {"TRAFFIC_SIGN", false}, {"PERSON", false}, {"VEHICLE", false},
{"BIKE", false}, {"ROAD", false}, {"SIDEWALK", false}, {"ROAD_PAINT", false},
{"CURBSTONE", false}, {"CROSSWALK", false}, {"VEGETATION", false}, {"SKY", false}};

public:
explicit SegmentPointCloudFusionNode(const rclcpp::NodeOptions & options);

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,134 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for Segmentation Pointcloud Fusion Node",
"type": "object",
"definitions": {
"segmentation_pointcloud_fusion": {
"type": "object",
"properties": {
"filter_semantic_label_target": {
"type": "object",
"properties": {
"UNKNOWN": {
"type": "boolean",
"description": "If true, UNKNOWN class of semantic will be filtered.",
"default": false
},
"BUILDING": {
"type": "boolean",
"description": "If true, BUILDING class of semantic will be filtered.",
"default": true
},
"WALL": {
"type": "boolean",
"description": "If true, WALL class of semantic will be filtered.",
"default": true
},
"OBSTACLE": {
"type": "boolean",
"description": "If true, OBSTACLE class of semantic will be filtered.",
"default": false
},
"TRAFFIC_LIGHT": {
"type": "boolean",
"description": "If true, TRAFFIC_LIGHT class of semantic will be filtered.",
"default": false
},
"TRAFFIC_SIGN": {
"type": "boolean",
"description": "If true, TRAFFIC_SIGN class of semantic will be filtered.",
"default": false
},
"PERSON": {
"type": "boolean",
"description": "If true, PERSON class of semantic will be filtered.",
"default": false
},
"VEHICLE": {
"type": "boolean",
"description": "If true, VEHICLE class of semantic will be filtered.",
"default": false
},
"BIKE": {
"type": "boolean",
"description": "If true, BIKE class of semantic will be filtered.",
"default": false
},
"ROAD": {
"type": "boolean",
"description": "If true, ROAD class of semantic will be filtered.",
"default": true
},
"SIDEWALK": {
"type": "boolean",
"description": "If true, SIDEWALK class of semantic will be filtered.",
"default": false
},
"ROAD_PAINT": {
"type": "boolean",
"description": "If true, ROAD_PAINT class of semantic will be filtered.",
"default": false
},
"CURBSTONE": {
"type": "boolean",
"description": "If true, CURBSTONE class of semantic will be filtered.",
"default": false
},
"CROSSWALK": {
"type": "boolean",
"description": "If true, CROSSWALK class of semantic will be filtered.",
"default": false
},
"VEGETATION": {
"type": "boolean",
"description": "If true, VEGETATION class of semantic will be filtered.",
"default": true
},
"SKY": {
"type": "boolean",
"description": "If true, SKY class of semantic will be filtered.",
"default": false
}
},
"required": [
"UNKNOWN",
"BUILDING",
"WALL",
"OBSTACLE",
"TRAFFIC_LIGHT",
"TRAFFIC_SIGN",
"PERSON",
"VEHICLE",
"BIKE",
"ROAD",
"SIDEWALK",
"ROAD_PAINT",
"CURBSTONE",
"CROSSWALK",
"VEGETATION",
"SKY"
]
},
"filter_distance_threshold": {
"type": "number",
"description": "A maximum distance of pointcloud to apply filter [m].",
"default": 60.0,
"minimum": 0.0
}
},
"required": ["filter_semantic_label_target", "filter_distance_threshold"]
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/segmentation_pointcloud_fusion"
}
},
"required": ["ros__parameters"]
}
},
"required": ["/**"]
}
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,13 @@ SegmentPointCloudFusionNode::SegmentPointCloudFusionNode(const rclcpp::NodeOptio
: FusionNode<PointCloud2, PointCloud2, Image>("segmentation_pointcloud_fusion", options)
{
filter_distance_threshold_ = declare_parameter<float>("filter_distance_threshold");
filter_semantic_label_target_ =
declare_parameter<std::vector<bool>>("filter_semantic_label_target");
for (auto & item : filter_semantic_label_target_list_) {
item.second = declare_parameter<bool>("filter_semantic_label_target." + item.first);
}
for (const auto & item : filter_semantic_label_target_list_) {
RCLCPP_INFO(
this->get_logger(), "filter_semantic_label_target: %s %d", item.first.c_str(), item.second);
}
}

void SegmentPointCloudFusionNode::preprocess(__attribute__((unused)) PointCloud2 & pointcloud_msg)
Expand Down Expand Up @@ -135,12 +140,12 @@ void SegmentPointCloudFusionNode::fuseOnSingleImage(
uint8_t semantic_id = mask.at<uint8_t>(
static_cast<uint16_t>(normalized_projected_point.y()),
static_cast<uint16_t>(normalized_projected_point.x()));
if (static_cast<size_t>(semantic_id) >= filter_semantic_label_target_.size()) {
if (static_cast<size_t>(semantic_id) >= filter_semantic_label_target_list_.size()) {
copyPointCloud(
input_pointcloud_msg, point_step, global_offset, output_cloud, output_pointcloud_size);
continue;
}
if (!filter_semantic_label_target_.at(semantic_id)) {
if (!filter_semantic_label_target_list_.at(semantic_id).second) {
copyPointCloud(
input_pointcloud_msg, point_step, global_offset, output_cloud, output_pointcloud_size);
}
Expand Down

0 comments on commit 6afc0e0

Please sign in to comment.