From 7e329c5e759bf76e276a0a9f0555af5ef930e9a1 Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Wed, 6 Sep 2023 03:50:08 +0900 Subject: [PATCH 01/12] refactor: add JSON Schema and remove default values in `declare_parameter()` Signed-off-by: ktro2828 --- .../schema/pointpainting.schema.json | 152 ++++++++++++++++++ .../schema/roi_cluster_fusion.schema.json | 92 +++++++++++ .../roi_detected_object_fusion.schema.json | 70 ++++++++ .../schema/roi_sync.schema.json | 44 +++++ .../src/pointpainting_fusion/node.cpp | 60 +++---- 5 files changed, 389 insertions(+), 29 deletions(-) create mode 100644 perception/image_projection_based_fusion/schema/pointpainting.schema.json create mode 100644 perception/image_projection_based_fusion/schema/roi_cluster_fusion.schema.json create mode 100644 perception/image_projection_based_fusion/schema/roi_detected_object_fusion.schema.json create mode 100644 perception/image_projection_based_fusion/schema/roi_sync.schema.json diff --git a/perception/image_projection_based_fusion/schema/pointpainting.schema.json b/perception/image_projection_based_fusion/schema/pointpainting.schema.json new file mode 100644 index 0000000000000..036628d72e70a --- /dev/null +++ b/perception/image_projection_based_fusion/schema/pointpainting.schema.json @@ -0,0 +1,152 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Point Painting Fusion Node", + "type": "object", + "definitions": { + "pointpainting": { + "type": "object", + "properties": { + "model_params": { + "type": "object", + "description": "Parameters for model configuration.", + "properties": { + "class_names": { + "type": "array", + "description": "An array of class names will be predicted.", + "default": ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"], + "uniqueItems": true + }, + "paint_class_names": { + "type": "array", + "description": "An array of class names will be painted by PointPainting", + "default": ["CAR", "BICYCLE", "PEDESTRIAN"], + "uniqueItems": true + }, + "point_feature_size": { + "type": "integer", + "description": "A number of channels of point feature layer.", + "default": 7 + }, + "max_voxel_size": { + "type": "integer", + "description": "A maximum size of voxel grid.", + "default": 40000 + }, + "point_cloud_range": { + "type": "array", + "description": "An array of distance ranges of each class, this must have same length with `class_names`.", + "default": [-121.6, -76.8, -3.0, 121.6, 76.8, 5.0] + }, + "voxel_size": { + "type": "array", + "description": "An array of voxel grid sizes for PointPainting, this must have same length with `paint_class_names`.", + "default": [0.32, 0.32, 8.0] + }, + "down_sample_factor": { + "type": "integer", + "description": "A scale factor of downsampling points", + "default": 1, + "minimum": 1 + }, + "encoder_in_feature_size": { + "type": "integer", + "description": "A size of encoder input feature channels.", + "default": 12 + }, + "yaw_norm_thresholds": { + "type": "array", + "description": "An array of distance threshold values of norm of yaw [rad].", + "default": [0.3, 0.3, 0.3, 0.3, 0.0], + "minimum": 0.0, + "maximum": 1.0 + }, + "has_twist": { + "type": "boolean", + "description": "Indicates whether the model outputs twist value.", + "default": false + } + } + }, + "densification_params": { + "type": "object", + "description": "Parameters for pointcloud densification.", + "properties": { + "world_frame_id": { + "type": "string", + "description": "A name of frame id where world coordinates system is defined with respect to.", + "default": "map" + }, + "num_past_frames": { + "type": "integer", + "description": "A number of past frames to be considered as same input frame.", + "default": 0, + "minimum": 0 + } + } + }, + "post_process_params": { + "type": "object", + "properties": { + "score_threshold": { + "type": "number", + "description": "A threshold value of existence probability score, all of objects with score less than this threshold are ignored.", + "default": 0.4, + "minimum": 0.0, + "maximum": 1.0 + }, + "circle_nms_dist_threshold": { + "type": "number", + "description": "", + "default": 0.3, + "minimum": 0.0, + "maximum": 1.0 + }, + "iou_nms_target_class_names": { + "type": "array", + "description": "An array of class names to be target in NMS.", + "default": ["CAR"], + "uniqueItems": true + }, + "iou_search_distance_2d": { + "type": "number", + "description": "A maximum distance value to search the nearest objects.", + "default": 10.0, + "minimum": 0.0 + }, + "iou_nms_threshold": { + "type": "number", + "description": "A threshold value of NMS using IoU score.", + "default": 0.1, + "minimum": 0.0, + "maximum": 1.0 + } + } + }, + "omp_params": { + "type": "object", + "properties": { + "num_threads": { + "type": "integer", + "description": "The number of threads that is set to the environment variable OMP_NUM_THREADS.", + "default": 1, + "minimum": 1 + } + } + } + }, + "required": ["model_params", "densification_params", "post_process_params", "omp_params"] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/pointpainting" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/perception/image_projection_based_fusion/schema/roi_cluster_fusion.schema.json b/perception/image_projection_based_fusion/schema/roi_cluster_fusion.schema.json new file mode 100644 index 0000000000000..bfedf50811ed0 --- /dev/null +++ b/perception/image_projection_based_fusion/schema/roi_cluster_fusion.schema.json @@ -0,0 +1,92 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for RoI Cluster Fusion Node", + "type": "object", + "definitions": { + "roi_cluster_fusion": { + "type": "object", + "properties": { + "use_iou": { + "type": "boolean", + "description": "If this parameter is true, calculate the common IoU score.", + "default": false + }, + "use_iou_x": { + "type": "boolean", + "description": "If this parameter is true, compute the IoU score in the x-direction", + "default": true + }, + "use_iou_y": { + "type": "boolean", + "description": "If this parameter is true, calculate the IoU score in the y-direction.", + "default": false + }, + "use_cluster_semantic_type": { + "type": "boolean", + "description": "If this parameter is false, label of cluster objects will be reset to UNKNOWN.", + "default": false + }, + "only_allow_inside_cluster": { + "type": "boolean", + "description": "If this parameter is true, only clusters in which all their points are inside the RoI can be assigned to the RoI.", + "default": true + }, + "roi_scale_factor": { + "type": "number", + "description": "A scale factor for resizing RoI while checking if cluster points are inside the RoI.", + "default": 1.1, + "minimum": 1.0, + "maximum": 2.0 + }, + "iou_threshold": { + "type": "number", + "description": "An IoU score threshold. Note that the total IoU score is the sum of the IoU scores that are set to true in use_iou, use_iou_x and use_iou_y.", + "default": 0.3, + "minimum": 0.0 + }, + "unknown_iou_threshold": { + "type": "number", + "description": "A threshold value of IoU score for objects labeled UNKNOWN.", + "default": 0.1, + "minimum": 0.0, + "maximum": 1.0 + }, + "remove_unknown": { + "type": "boolean", + "description": "If this parameter is true, all of objects labeled UNKNOWN will be removed in post-process.", + "default": false + }, + "trust_distance": { + "type": "number", + "description": "A distance value to filtering out objects with its distance.", + "default": 100.0, + "minimum": 0.0 + } + }, + "required": [ + "use_iou", + "use_iou_x", + "use_iou_y", + "use_cluster_semantic_type", + "only_allow_inside_cluster", + "roi_scale_factor", + "iou_threshold", + "unknown_iou_threshold", + "remove_unknown", + "trust_distance" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/roi_cluster_fusion" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/perception/image_projection_based_fusion/schema/roi_detected_object_fusion.schema.json b/perception/image_projection_based_fusion/schema/roi_detected_object_fusion.schema.json new file mode 100644 index 0000000000000..a77f12e5f4ef4 --- /dev/null +++ b/perception/image_projection_based_fusion/schema/roi_detected_object_fusion.schema.json @@ -0,0 +1,70 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for RoI Detected Object Fusion Node", + "type": "object", + "definitions": { + "roi_detected_object_fusion": { + "type": "object", + "properties": { + "passthrough_lower_bound_probability_thresholds": { + "type": "array", + "description": "An array of object probability thresholds. The objects that have higher probability than their respective thresholds are kept.", + "default": [0.35, 0.35, 0.35, 0.35, 0.35, 0.35, 0.35, 0.5] + }, + "trust_distances": { + "type": "array", + "description": "An array of object distances thresholds. The objects that are closer than their respective thresholds kept.", + "default": [50.0, 100.0, 100.0, 100.0, 100.0, 50.0, 50.0, 50.0] + }, + "min_iou_threshold": { + "type": "number", + "description": "An Iou threshold", + "default": 0.5, + "minimum": 0.0, + "maximum": 1.0 + }, + "roi_probability_threshold": { + "type": "number", + "description": "A object probability threshold.", + "default": 0.5, + "minimum": 0.0, + "maximum": 1.0 + }, + "use_roi_probability": { + "type": "boolean", + "description": "If this parameter is true, the objects are filtered out with their RoI probabilities.", + "default": false + }, + "can_assign_matrix": { + "type": "array", + "description": "An NxN matrix, where N represents the number of classes. A value 1 indicates that it is assignable, while a value of 0 indicates not.", + "default": [ + 1, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 1, 1, 1, 1, + 0, 0, 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 0, 0, 0, 0, 0, 1, 1, 1, 0, 0, + 0, 0, 0, 1, 1, 1 + ] + } + }, + "required": [ + "passthrough_lower_bound_probability_thresholds", + "trust_distances", + "min_iou_threshold", + "roi_probability_threshold", + "use_roi_probability", + "can_assign_matrix" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/roi_detected_object_fusion" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/perception/image_projection_based_fusion/schema/roi_sync.schema.json b/perception/image_projection_based_fusion/schema/roi_sync.schema.json new file mode 100644 index 0000000000000..20bb816a56d02 --- /dev/null +++ b/perception/image_projection_based_fusion/schema/roi_sync.schema.json @@ -0,0 +1,44 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Synchronization of RoI Fusion Nodes", + "type": "object", + "definitions": { + "roi_sync": { + "type": "object", + "properties": { + "input_offset_ms": { + "type": "array", + "description": "An array of timestamp offsets for each camera [ms].", + "default": [61.67, 111.67, 45.0, 28.33, 78.33, 95.0] + }, + "timeout_ms": { + "type": "number", + "description": "A timeout value can be assigned within a single frame [ms].", + "default": 70.0, + "minimum": 1.0, + "maximum": 100.0 + }, + "match_threshold_ms": { + "type": "number", + "description": "A maximum threshold value to synchronize RoIs from multiple cameras [ms].", + "default": 50.0, + "minimum": 0.0, + "maximum": 100.0 + } + }, + "required": ["input_offset_ms", "timeout_ms", "match_threshold_ms"] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/roi_sync" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} diff --git a/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp b/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp index 48ef3d26806c8..76b561f677c0f 100644 --- a/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/pointpainting_fusion/node.cpp @@ -95,28 +95,29 @@ inline bool isUnknown(int label2d) PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & options) : FusionNode("pointpainting_fusion", options) { - omp_num_threads_ = this->declare_parameter("omp_num_threads", 1); + omp_num_threads_ = this->declare_parameter("omp_params.num_threads"); const float score_threshold = - static_cast(this->declare_parameter("score_threshold", 0.4)); - const float circle_nms_dist_threshold = - static_cast(this->declare_parameter("circle_nms_dist_threshold", 1.5)); + static_cast(this->declare_parameter("post_process_params.score_threshold")); + const float circle_nms_dist_threshold = static_cast( + this->declare_parameter("post_process_params.circle_nms_dist_threshold")); const auto yaw_norm_thresholds = - this->declare_parameter>("yaw_norm_thresholds"); + this->declare_parameter>("model_params.yaw_norm_thresholds"); // densification param const std::string densification_world_frame_id = - this->declare_parameter("densification_world_frame_id", "map"); + this->declare_parameter("densification_params.world_frame_id"); const int densification_num_past_frames = - this->declare_parameter("densification_num_past_frames", 0); + this->declare_parameter("densification_params.num_past_frames"); // network param - const std::string trt_precision = this->declare_parameter("trt_precision", "fp16"); - const std::string encoder_onnx_path = this->declare_parameter("encoder_onnx_path", ""); - const std::string encoder_engine_path = this->declare_parameter("encoder_engine_path", ""); - const std::string head_onnx_path = this->declare_parameter("head_onnx_path", ""); - const std::string head_engine_path = this->declare_parameter("head_engine_path", ""); - - class_names_ = this->declare_parameter>("class_names"); + const std::string trt_precision = this->declare_parameter("trt_precision"); + const std::string encoder_onnx_path = this->declare_parameter("encoder_onnx_path"); + const std::string encoder_engine_path = + this->declare_parameter("encoder_engine_path"); + const std::string head_onnx_path = this->declare_parameter("head_onnx_path"); + const std::string head_engine_path = this->declare_parameter("head_engine_path"); + + class_names_ = this->declare_parameter>("model_params.class_names"); const auto paint_class_names = - this->declare_parameter>("paint_class_names"); + this->declare_parameter>("model_params.paint_class_names"); std::vector classes_{"CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"}; if ( std::find(paint_class_names.begin(), paint_class_names.end(), "TRUCK") != @@ -138,17 +139,17 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt isClassTable_.erase(cls); } } - has_twist_ = this->declare_parameter("has_twist", false); - const std::size_t point_feature_size = - static_cast(this->declare_parameter("point_feature_size")); + has_twist_ = this->declare_parameter("model_params.has_twist"); + const std::size_t point_feature_size = static_cast( + this->declare_parameter("model_params.point_feature_size")); const std::size_t max_voxel_size = - static_cast(this->declare_parameter("max_voxel_size")); - pointcloud_range = this->declare_parameter>("point_cloud_range"); - const auto voxel_size = this->declare_parameter>("voxel_size"); - const std::size_t downsample_factor = - static_cast(this->declare_parameter("downsample_factor")); - const std::size_t encoder_in_feature_size = - static_cast(this->declare_parameter("encoder_in_feature_size")); + static_cast(this->declare_parameter("model_params.max_voxel_size")); + pointcloud_range = this->declare_parameter>("model_params.point_cloud_range"); + const auto voxel_size = this->declare_parameter>("model_params.voxel_size"); + const std::size_t downsample_factor = static_cast( + this->declare_parameter("model_params.downsample_factor")); + const std::size_t encoder_in_feature_size = static_cast( + this->declare_parameter("model_params.encoder_in_feature_size")); const auto allow_remapping_by_area_matrix = this->declare_parameter>("allow_remapping_by_area_matrix"); const auto min_area_matrix = this->declare_parameter>("min_area_matrix"); @@ -172,10 +173,11 @@ PointPaintingFusionNode::PointPaintingFusionNode(const rclcpp::NodeOptions & opt { centerpoint::NMSParams p; p.nms_type_ = centerpoint::NMS_TYPE::IoU_BEV; - p.target_class_names_ = - this->declare_parameter>("iou_nms_target_class_names"); - p.search_distance_2d_ = this->declare_parameter("iou_nms_search_distance_2d"); - p.iou_threshold_ = this->declare_parameter("iou_nms_threshold"); + p.target_class_names_ = this->declare_parameter>( + "post_process_params.iou_nms_target_class_names"); + p.search_distance_2d_ = + this->declare_parameter("post_process_params.iou_nms_search_distance_2d"); + p.iou_threshold_ = this->declare_parameter("post_process_params.iou_nms_threshold"); iou_bev_nms_.setParameters(p); } From 193ab743e712acbf12de1a35869f2996d7e97fe7 Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Wed, 6 Sep 2023 15:36:30 +0900 Subject: [PATCH 02/12] refactor: update configuration file Signed-off-by: ktro2828 --- .../config/pointpainting.param.yaml | 38 +++++++++++-------- 1 file changed, 22 insertions(+), 16 deletions(-) diff --git a/perception/image_projection_based_fusion/config/pointpainting.param.yaml b/perception/image_projection_based_fusion/config/pointpainting.param.yaml index e1be5426cba4b..7ea5f53ac2b96 100755 --- a/perception/image_projection_based_fusion/config/pointpainting.param.yaml +++ b/perception/image_projection_based_fusion/config/pointpainting.param.yaml @@ -1,18 +1,24 @@ /**: ros__parameters: - class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] - paint_class_names: ["CAR", "BICYCLE", "PEDESTRIAN"] - point_feature_size: 7 # x, y, z, time-lag and car, pedestrian, bicycle - max_voxel_size: 40000 - point_cloud_range: [-121.6, -76.8, -3.0, 121.6, 76.8, 5.0] - voxel_size: [0.32, 0.32, 8.0] - downsample_factor: 1 - encoder_in_feature_size: 12 - yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] - # post-process params - circle_nms_dist_threshold: 0.3 - iou_nms_target_class_names: ["CAR"] - iou_nms_search_distance_2d: 10.0 - iou_nms_threshold: 0.1 - # omp params - omp_num_threads: 1 + model_params: + class_names: ["CAR", "TRUCK", "BUS", "BICYCLE", "PEDESTRIAN"] + paint_class_names: ["CAR", "BICYCLE", "PEDESTRIAN"] + point_feature_size: 7 # x, y, z, time-lag and car, pedestrian, bicycle + max_voxel_size: 40000 + point_cloud_range: [-121.6, -76.8, -3.0, 121.6, 76.8, 5.0] + voxel_size: [0.32, 0.32, 8.0] + downsample_factor: 1 + encoder_in_feature_size: 12 + yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] + densification_params: + world_frame_id: "map" + num_past_frames: 0 + post_process_params: + # post-process params + circle_nms_dist_threshold: 0.3 + iou_nms_target_class_names: ["CAR"] + iou_nms_search_distance_2d: 10.0 + iou_nms_threshold: 0.1 + omp_params: + # omp params + omp_num_threads: 1 From fdcfbd44b9eee1f533edd4d86b2b7e38e51a95a8 Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Wed, 6 Sep 2023 16:03:09 +0900 Subject: [PATCH 03/12] refactor: add configuration file and update launcher to load this Signed-off-by: ktro2828 --- .../config/roi_cluster_fusion.param.yaml | 12 +++++ .../launch/pointpainting_fusion.launch.xml | 3 -- .../launch/roi_cluster_fusion.launch.xml | 15 +----- .../schema/roi_cluster_fusion.schema.json | 54 ++++++++++--------- .../roi_detected_object_fusion.schema.json | 4 +- .../schema/roi_sync.schema.json | 3 +- 6 files changed, 46 insertions(+), 45 deletions(-) create mode 100644 perception/image_projection_based_fusion/config/roi_cluster_fusion.param.yaml diff --git a/perception/image_projection_based_fusion/config/roi_cluster_fusion.param.yaml b/perception/image_projection_based_fusion/config/roi_cluster_fusion.param.yaml new file mode 100644 index 0000000000000..90ba841d53b2d --- /dev/null +++ b/perception/image_projection_based_fusion/config/roi_cluster_fusion.param.yaml @@ -0,0 +1,12 @@ +/**: + ros__parameters: + fusion_distance: 100.0 + trust_object_distance: 100.0 + trust_object_iou_mode: "iou" + non_trust_object_iou_mode: "iou_x" + use_cluster_semantic_type: false + only_allow_inside_cluster: true + roi_scale_factor: 1.1 + iou_threshold: 0.65 + unknown_iou_threshold: 0.1 + remove_unknown: true diff --git a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml index e15737f5ed222..c07c4a02884c2 100644 --- a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml @@ -43,9 +43,6 @@ - - - diff --git a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml index 60f6f943b8cda..fa1c9b05ddd57 100644 --- a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml @@ -18,10 +18,8 @@ + - - - @@ -46,17 +44,8 @@ - - - - - - - - - - + diff --git a/perception/image_projection_based_fusion/schema/roi_cluster_fusion.schema.json b/perception/image_projection_based_fusion/schema/roi_cluster_fusion.schema.json index bfedf50811ed0..fc32e9d6d3d8b 100644 --- a/perception/image_projection_based_fusion/schema/roi_cluster_fusion.schema.json +++ b/perception/image_projection_based_fusion/schema/roi_cluster_fusion.schema.json @@ -6,20 +6,29 @@ "roi_cluster_fusion": { "type": "object", "properties": { - "use_iou": { - "type": "boolean", - "description": "If this parameter is true, calculate the common IoU score.", - "default": false + "fusion_distance": { + "type": "number", + "description": "If the detected object's distance is less than its value, the fusion will be processed.", + "default": 100.0, + "minimum": 0.0 }, - "use_iou_x": { - "type": "boolean", - "description": "If this parameter is true, compute the IoU score in the x-direction", - "default": true + "trust_object_distance": { + "type": "number", + "description": "If the detected object's distance is less than its value, IoU method specified in `trust_object_iou_mode` is used, otherwise `non_trust_object_iou_mode` is used.", + "default": 100.0, + "minimum": 0.0 }, - "use_iou_y": { - "type": "boolean", - "description": "If this parameter is true, calculate the IoU score in the y-direction.", - "default": false + "trust_object_iou_mode": { + "type": "string", + "description": "Name of IoU method applied to the objects in range of [0.0, `trust_distance`].", + "default": "iou", + "enum": ["iou", "iou_x", "iou_y"] + }, + "non_trust_object_iou_mode": { + "type": "string", + "description": "Name of IoU method applied to the objects in range of [`trust_distance`, `fusion_distance`], if `trust_distance` < `fusion_distance`.", + "default": "iou_x", + "enum": ["iou", "iou_x", "iou_y"] }, "use_cluster_semantic_type": { "type": "boolean", @@ -41,8 +50,9 @@ "iou_threshold": { "type": "number", "description": "An IoU score threshold. Note that the total IoU score is the sum of the IoU scores that are set to true in use_iou, use_iou_x and use_iou_y.", - "default": 0.3, - "minimum": 0.0 + "default": 0.65, + "minimum": 0.0, + "maximum": 1.0 }, "unknown_iou_threshold": { "type": "number", @@ -55,25 +65,19 @@ "type": "boolean", "description": "If this parameter is true, all of objects labeled UNKNOWN will be removed in post-process.", "default": false - }, - "trust_distance": { - "type": "number", - "description": "A distance value to filtering out objects with its distance.", - "default": 100.0, - "minimum": 0.0 } }, "required": [ - "use_iou", - "use_iou_x", - "use_iou_y", + "fusion_distance", + "trust_object_distance", + "trust_object_iou_mode", + "non_trust_object_iou_mode", "use_cluster_semantic_type", "only_allow_inside_cluster", "roi_scale_factor", "iou_threshold", "unknown_iou_threshold", - "remove_unknown", - "trust_distance" + "remove_unknown" ] } }, diff --git a/perception/image_projection_based_fusion/schema/roi_detected_object_fusion.schema.json b/perception/image_projection_based_fusion/schema/roi_detected_object_fusion.schema.json index a77f12e5f4ef4..3030be1305d56 100644 --- a/perception/image_projection_based_fusion/schema/roi_detected_object_fusion.schema.json +++ b/perception/image_projection_based_fusion/schema/roi_detected_object_fusion.schema.json @@ -13,12 +13,12 @@ }, "trust_distances": { "type": "array", - "description": "An array of object distances thresholds. The objects that are closer than their respective thresholds kept.", + "description": "An array of object distances thresholds. Any objects that is farther than this value will be skipped in the clustering process, but will still be published.", "default": [50.0, 100.0, 100.0, 100.0, 100.0, 50.0, 50.0, 50.0] }, "min_iou_threshold": { "type": "number", - "description": "An Iou threshold", + "description": "An Iou score threshold.", "default": 0.5, "minimum": 0.0, "maximum": 1.0 diff --git a/perception/image_projection_based_fusion/schema/roi_sync.schema.json b/perception/image_projection_based_fusion/schema/roi_sync.schema.json index 20bb816a56d02..b60717ba77d1f 100644 --- a/perception/image_projection_based_fusion/schema/roi_sync.schema.json +++ b/perception/image_projection_based_fusion/schema/roi_sync.schema.json @@ -25,8 +25,7 @@ "minimum": 0.0, "maximum": 100.0 } - }, - "required": ["input_offset_ms", "timeout_ms", "match_threshold_ms"] + } } }, "properties": { From 0185e10616b837a580b5a673325c98c05a25dc93 Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Tue, 12 Sep 2023 22:15:32 +0900 Subject: [PATCH 04/12] refactor: update funsion node configuration Signed-off-by: ktro2828 --- .../config/roi_sync.param.yaml | 7 ++++ .../launch/roi_cluster_fusion.launch.xml | 17 --------- .../roi_detected_object_fusion.launch.xml | 2 -- .../schema/roi_sync.schema.json | 36 +++++++++++++++++++ .../src/fusion_node.cpp | 19 +++++----- 5 files changed, 53 insertions(+), 28 deletions(-) diff --git a/perception/image_projection_based_fusion/config/roi_sync.param.yaml b/perception/image_projection_based_fusion/config/roi_sync.param.yaml index 21ba13787f1c0..a4e96ff291a49 100644 --- a/perception/image_projection_based_fusion/config/roi_sync.param.yaml +++ b/perception/image_projection_based_fusion/config/roi_sync.param.yaml @@ -3,3 +3,10 @@ input_offset_ms: [61.67, 111.67, 45.0, 28.33, 78.33, 95.0] timeout_ms: 70.0 match_threshold_ms: 50.0 + image_buffer_size: 15 + filter_scope_minx: -100.0 + filter_scope_miny: -100.0 + filter_scope_minz: -100.0 + filter_scope_maxx: 100.0 + filter_scope_maxy: 100.0 + filter_scope_maxz: 100.0 diff --git a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml index fa1c9b05ddd57..40374f2b8ab29 100644 --- a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml @@ -21,19 +21,9 @@ - - - - - - - - - - @@ -78,13 +68,6 @@ - - - - - - - diff --git a/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml index b6165fc7c87d2..5c77b3a1f64d0 100644 --- a/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml @@ -26,7 +26,6 @@ - @@ -72,7 +71,6 @@ - diff --git a/perception/image_projection_based_fusion/schema/roi_sync.schema.json b/perception/image_projection_based_fusion/schema/roi_sync.schema.json index b60717ba77d1f..4df0193c65ebf 100644 --- a/perception/image_projection_based_fusion/schema/roi_sync.schema.json +++ b/perception/image_projection_based_fusion/schema/roi_sync.schema.json @@ -24,6 +24,42 @@ "default": 50.0, "minimum": 0.0, "maximum": 100.0 + }, + "image_buffer_size": { + "type": "integer", + "description": "The number of image buffer size for debug.", + "default": 15, + "minimum": 1 + }, + "filter_scope_minx": { + "type": "number", + "description": "Minimum x position to be considered for debug [m].", + "default": -100.0 + }, + "filter_scope_miny": { + "type": "number", + "description": "Minimum y position to be considered for debug [m].", + "default": -100.0 + }, + "filter_scope_minz": { + "type": "number", + "description": "Minimum z position to be considered for debug [m].", + "default": -100.0 + }, + "filter_scope_maxx": { + "type": "number", + "description": "Maximum x position to be considered for debug [m].", + "default": 100.0 + }, + "filter_scope_maxy": { + "type": "number", + "description": "Maximum y position to be considered for debug [m].", + "default": 100.0 + }, + "filter_scope_maxz": { + "type": "number", + "description": "Maximum z position [m].", + "default": 100.0 } } } diff --git a/perception/image_projection_based_fusion/src/fusion_node.cpp b/perception/image_projection_based_fusion/src/fusion_node.cpp index b01a910aaded1..3d1345f75752b 100644 --- a/perception/image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/image_projection_based_fusion/src/fusion_node.cpp @@ -46,7 +46,7 @@ FusionNode::FusionNode( : Node(node_name, options), tf_buffer_(this->get_clock()), tf_listener_(tf_buffer_) { // set rois_number - rois_number_ = static_cast(declare_parameter("rois_number", 1)); + rois_number_ = static_cast(declare_parameter("rois_number")); if (rois_number_ < 1) { RCLCPP_WARN( this->get_logger(), "minimum rois_number is 1. current rois_number is %zu", rois_number_); @@ -80,7 +80,7 @@ FusionNode::FusionNode( "/sensing/camera/camera" + std::to_string(roi_i) + "/image_rect_color"); } - input_offset_ms_ = declare_parameter("input_offset_ms", std::vector{}); + input_offset_ms_ = declare_parameter>("input_offset_ms"); if (!input_offset_ms_.empty() && rois_number_ != input_offset_ms_.size()) { throw std::runtime_error("The number of offsets does not match the number of topics."); } @@ -122,7 +122,7 @@ FusionNode::FusionNode( // debugger if (declare_parameter("debug_mode", false)) { std::size_t image_buffer_size = - static_cast(declare_parameter("image_buffer_size", 15)); + static_cast(declare_parameter("image_buffer_size")); debugger_ = std::make_shared(this, rois_number_, image_buffer_size, input_camera_topics_); } @@ -136,14 +136,15 @@ FusionNode::FusionNode( stop_watch_ptr_->tic("cyclic_time"); stop_watch_ptr_->tic("processing_time"); } + // cspell: ignore minx, maxx, miny, maxy, minz, maxz // FIXME: use min_x instead of minx - filter_scope_minx_ = declare_parameter("filter_scope_minx", -100); - filter_scope_maxx_ = declare_parameter("filter_scope_maxx", 100); - filter_scope_miny_ = declare_parameter("filter_scope_miny", -100); - filter_scope_maxy_ = declare_parameter("filter_scope_maxy", 100); - filter_scope_minz_ = declare_parameter("filter_scope_minz", -100); - filter_scope_maxz_ = declare_parameter("filter_scope_maxz", 100); + filter_scope_minx_ = declare_parameter("filter_scope_minx"); + filter_scope_maxx_ = declare_parameter("filter_scope_maxx"); + filter_scope_miny_ = declare_parameter("filter_scope_miny"); + filter_scope_maxy_ = declare_parameter("filter_scope_maxy"); + filter_scope_minz_ = declare_parameter("filter_scope_minz"); + filter_scope_maxz_ = declare_parameter("filter_scope_maxz"); } template From 08c4622d1dd50205704da2dbae153d3617268370 Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Tue, 12 Sep 2023 22:41:25 +0900 Subject: [PATCH 05/12] docs: update the document for roi cluster fusion Signed-off-by: ktro2828 --- .../docs/images/roi_cluster_fusion_params.svg | 966 ++++++++++++++++++ .../docs/roi-cluster-fusion.md | 5 + 2 files changed, 971 insertions(+) create mode 100644 perception/image_projection_based_fusion/docs/images/roi_cluster_fusion_params.svg diff --git a/perception/image_projection_based_fusion/docs/images/roi_cluster_fusion_params.svg b/perception/image_projection_based_fusion/docs/images/roi_cluster_fusion_params.svg new file mode 100644 index 0000000000000..603dc6807082e --- /dev/null +++ b/perception/image_projection_based_fusion/docs/images/roi_cluster_fusion_params.svg @@ -0,0 +1,966 @@ + + + + + + + + + + +
+
+
+ use_iou +
+
+
+
+ use_iou +
+
+ + + + +
+
+
+ roi_scale_factor +
+
+
+
+ roi_scale_factor +
+
+ + + + +
+
+
+ unknown_iou_threshold +
+
+
+
+ unknown_iou_threshold +
+
+ + + + +
+
+
+ + use_iou_x /  y +
+
+
+
+
+
+ use_iou_x /  y +
+
+ + + + + + +
+
+
+ only_allow_inside_cluster +
+
+
+
+ only_allow_inside_cluster +
+
+ + + + +
+
+
+ iou_threshold +
+
+
+
+ iou_threshold +
+
+ + + + + + + + +
+
+
+ Is UNKNOWN object? +
+
+
+
+ Is UNKNOWN object? +
+
+ + + + + + +
+
+
+ + IoU threshold < IoU score? + +
+
+
+
+ IoU threshold < IoU score? +
+
+ + + + + + + + + + + + +
+
+
+ IoU Score +
+
+
+
+ IoU Score +
+
+ + + + + + + + + + + + + + + + + + + + + +
+
+
+ Is Cluster RoI inside Detected RoI? +
+
+
+
+ Is Cluster RoI inside Detected RoI? +
+
+ + + + + + + + +
+
+
+ Fused Cluster +
+
+
+
+ Fused Cluster +
+
+ + + + + + +
+
+
+ Unfused Cluster +
+
+
+
+ Unfused Cluster +
+
+ + + + + + + + +
+
+
+ Fusion Target Cluster
&
Detected RoI
+
+
+
+
+ Fusion Target Cluster... +
+
+ + + + +
+
+
+ + Check whether + the cluster RoI (inner) + is fully contained within + the scaled detected RoI (outer) + . +
+
+ *NOTE* +
+ Because the cluster RoI is calculated with the points projected on the image, our recommended scale factor is [1.1, 1.5] . +
+ Otherwise, set + only_allow_inside_cluster + to + False + . +
+
+
+
+
+
+ Check whether the cluster RoI (inner) is fully contained within the scaled... +
+
+ + + + +
+
+
+ Unfused Cluster +
+
+
+
+ Unfused Cluster +
+
+ + + + + + + + + + + +
+
+
+ + + roi_scale_factor
(>=1.0)
+
+
+
+
+
+
+ roi_scale_factor... +
+
+ + + + +
+
+
+ + Check whether the IoU score between + the cluster RoI + and + the detected RoI + is greater than the threshold. +
+
+ **NOTE** +
+ Our default threshold is 0.65 with + only_allow_inside_cluster + is + True + . +
+ Also, please try the bigger score threshold and set + only_allow_inside_cluster + to + False + depending on your 2D RoI detector performance. +
+
+
+
+
+
+ Check whether the IoU score between the cluster RoI and the detected RoI is greater than the thr... +
+
+ + + + + + +
+
+
+
    +
  • + IoU = Intersection Area / Union Area +
  • +
  • + IoU X = Intersection Width / Union Width +
  • +
  • + IoU Y = Intersection Height / Union Height +
  • +
+
+
+
+
+ IoU = Intersection Area / Union AreaIoU X = Intersectio... +
+
+ + + + +
+
+
+ + Nodes overview + +
+
+
+
+ Nodes overview +
+
+ + + + +
+
+
+ Numeric Parameter +
+
+
+
+ Numeric Parameter +
+
+ + + + +
+
+
+ Result +
+
+
+
+ Result +
+
+ + + + + + + + +
+
+
+ Boolean Parameter +
+
+
+
+ Boolean Parameter +
+
+ + + + +
+
+
+ + true + +
+
+
+
+ true +
+
+ + + + +
+
+
+ + false + +
+
+
+
+ false +
+
+ + + + + + + + +
+
+
+ Condition +
+
+
+
+ Condition +
+
+ + + + +
+
+
+ + true + +
+
+
+
+ true +
+
+ + + + +
+
+
+ + false + +
+
+
+
+ false +
+
+ + + + +
+
+
+ use_cluster_semantic_type +
+
+
+
+ use_cluster_semantic_type +
+
+ + + + +
+
+
+ + Objects +
+ w/ Semantic Label +
+
+
+
+
+ Objects... +
+
+ + + + + + +
+
+
+ + All objects are set to +
+ UNKOWN Label +
+
+
+
+
+
+ All objects are set to... +
+
+ + + + + + + + +
+
+
+ Fusion Target Cluster +
+
+
+
+ Fusion Target Cluster +
+
+ + + + +
+
+
+ trust_distance +
+
+
+
+ trust_distance +
+
+ + + + + + +
+
+
+ + Is Cluster closer than + trust_distance + ? + +
+
+
+
+ Is Cluster closer than trust_... +
+
+ + + + + + + + + + + + +
+
+
+ + Input Cluster + +
+
+
+
+ Input Cluster +
+
+ + + + +
+
+
+ Pre-Process +
+
+
+
+ Pre-Process +
+
+ + + + +
+
+
+ Fusion Process +
+
+
+
+ Fusion Process +
+
+ + + + +
+
+
+ Post-Process +
+
+
+
+ Post-Process +
+
+ + + + + + +
+
+
+ remove_unknown +
+
+
+
+ remove_unknown +
+
+ + + + + + +
+
+
+ Fused Cluster +
+
+
+
+ Fused Cluster +
+
+ + + + +
+
+
+ Is KNOWN object?
&&
0.1 <= RoI probability?
+
+
+
+
+ Is KNOWN object?... +
+
+ + + + + + +
+
+
+ Remove noise clusters, which are undetected by RoI detector, such as fog and exhaust gas. +
+
+
+
+ Remove noise clusters, which are undet... +
+
+ + + + +
+
+
+ + Output Fused Cluster + +
+
+
+
+ Output Fused Cluster +
+
+ + + + + + +
+ + + + Text is not SVG - cannot display + + +
diff --git a/perception/image_projection_based_fusion/docs/roi-cluster-fusion.md b/perception/image_projection_based_fusion/docs/roi-cluster-fusion.md index 03eaab2a3c6ca..8f34286f874b7 100644 --- a/perception/image_projection_based_fusion/docs/roi-cluster-fusion.md +++ b/perception/image_projection_based_fusion/docs/roi-cluster-fusion.md @@ -30,6 +30,11 @@ The clusters are projected onto image planes, and then if the ROIs of clusters a ## Parameters +The following figure is an inner pipeline of RoI cluster fusion node. +Please refer to it when you want to optimize parameters. + +![roi_cluster_fusion_params](./images/roi_cluster_fusion_params.svg) + ### Core Parameters | Name | Type | Description | From 8d688a7c4db0023cd2c883de9ea812c97f5bab9a Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Fri, 22 Sep 2023 18:00:26 +0900 Subject: [PATCH 06/12] docs: update documents Signed-off-by: ktro2828 --- ...ms.svg => roi_cluster_fusion_pipeline.svg} | 196 +++++++++--------- .../docs/roi-cluster-fusion.md | 6 +- 2 files changed, 101 insertions(+), 101 deletions(-) rename perception/image_projection_based_fusion/docs/images/{roi_cluster_fusion_params.svg => roi_cluster_fusion_pipeline.svg} (82%) diff --git a/perception/image_projection_based_fusion/docs/images/roi_cluster_fusion_params.svg b/perception/image_projection_based_fusion/docs/images/roi_cluster_fusion_pipeline.svg similarity index 82% rename from perception/image_projection_based_fusion/docs/images/roi_cluster_fusion_params.svg rename to perception/image_projection_based_fusion/docs/images/roi_cluster_fusion_pipeline.svg index 603dc6807082e..aaadfaf186dd2 100644 --- a/perception/image_projection_based_fusion/docs/images/roi_cluster_fusion_params.svg +++ b/perception/image_projection_based_fusion/docs/images/roi_cluster_fusion_pipeline.svg @@ -8,45 +8,69 @@ width="1680px" height="970px" viewBox="-0.5 -0.5 1680 970" - content="<mxfile host="app.diagrams.net" modified="2023-09-12T13:40:23.282Z" agent="Mozilla/5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) Chrome/116.0.0.0 Safari/537.36" etag="FWvtb0aLgxhX_0HQf0nn" version="21.7.0" type="google"><diagram name="Page-1" id="FLOA4M6UGa_QoeRYgYDe">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</diagram></mxfile>" + content="<mxfile host="app.diagrams.net" modified="2023-09-22T08:56:48.600Z" agent="Mozilla/5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) Chrome/117.0.0.0 Safari/537.36" etag="Ofs7qYSProiYeU6I9a5x" version="21.8.0" type="google"><diagram name="Page-1" id="FLOA4M6UGa_QoeRYgYDe">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</diagram></mxfile>" style="background-color: rgb(255, 255, 255);" > - +
-
+
- use_iou + + Check whether + the cluster RoI (inner) + is fully contained within + the scaled detected RoI (outer) + . +
+
+ *NOTE* +
+ Because the cluster RoI is calculated with the points projected on the image, our recommended scale factor is [1.1, 1.5] . +
+ Otherwise, set + only_allow_inside_cluster + to + False + . +
+
- use_iou + Check whether the cluster RoI (inner) is fully contained within the scaled... - +
- roi_scale_factor + use_iou
- roi_scale_factor + use_iou
@@ -88,15 +112,15 @@ use_iou_x /  y - - - + + +
@@ -105,7 +129,7 @@
- only_allow_inside_cluster + only_allow_inside_cluster @@ -128,8 +152,8 @@ - - + + @@ -148,8 +172,8 @@ Is UNKNOWN object? - - + + @@ -172,12 +196,12 @@ - - - - - - + + + + + + @@ -196,12 +220,12 @@ IoU Score - + - - + + @@ -209,17 +233,17 @@ - - - - - + + + + +
@@ -228,11 +252,9 @@
- Is Cluster RoI inside Detected RoI? + Is Cluster RoI inside Detected RoI? - - @@ -275,8 +297,8 @@ - - + + @@ -295,55 +317,13 @@ Fusion Target Cluster... - - - - -
-
-
- - Check whether - the cluster RoI (inner) - is fully contained within - the scaled detected RoI (outer) - . -
-
- *NOTE* -
- Because the cluster RoI is calculated with the points projected on the image, our recommended scale factor is [1.1, 1.5] . -
- Otherwise, set - only_allow_inside_cluster - to - False - . -
-
-
-
-
-
- Check whether the cluster RoI (inner) is fully contained within the scaled... -
-
- +
@@ -352,16 +332,16 @@
- Unfused Cluster + Unfused Cluster - - - - - - - + + + + + + + @@ -769,12 +749,12 @@ - - + + - - + + @@ -795,6 +775,24 @@ Input Cluster + + + + +
+
+
+ roi_scale_factor +
+
+
+
+ roi_scale_factor +
+
@@ -950,12 +948,14 @@ Output Fused Cluster - + - - + + + + diff --git a/perception/image_projection_based_fusion/docs/roi-cluster-fusion.md b/perception/image_projection_based_fusion/docs/roi-cluster-fusion.md index 8f34286f874b7..86d3a2fa070b2 100644 --- a/perception/image_projection_based_fusion/docs/roi-cluster-fusion.md +++ b/perception/image_projection_based_fusion/docs/roi-cluster-fusion.md @@ -30,10 +30,10 @@ The clusters are projected onto image planes, and then if the ROIs of clusters a ## Parameters -The following figure is an inner pipeline of RoI cluster fusion node. -Please refer to it when you want to optimize parameters. +The following figure is an inner pipeline overview of RoI cluster fusion node. +Please refer to it for your parameter settings. -![roi_cluster_fusion_params](./images/roi_cluster_fusion_params.svg) +![roi_cluster_fusion_pipeline](./images/roi_cluster_fusion_pipeline.svg) ### Core Parameters From 1cbd700d83a6c869ab0a20075f5b008a2e569e75 Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Thu, 28 Sep 2023 14:23:25 +0900 Subject: [PATCH 07/12] refactor: move `debug_mode` into `roi_sync.param.yaml` Signed-off-by: ktro2828 --- .../image_projection_based_fusion/config/roi_sync.param.yaml | 1 + .../launch/pointpainting_fusion.launch.xml | 3 --- .../launch/roi_cluster_fusion.launch.xml | 3 --- .../launch/roi_detected_object_fusion.launch.xml | 3 --- .../schema/roi_sync.schema.json | 5 +++++ 5 files changed, 6 insertions(+), 9 deletions(-) diff --git a/perception/image_projection_based_fusion/config/roi_sync.param.yaml b/perception/image_projection_based_fusion/config/roi_sync.param.yaml index a4e96ff291a49..f2e020344acb9 100644 --- a/perception/image_projection_based_fusion/config/roi_sync.param.yaml +++ b/perception/image_projection_based_fusion/config/roi_sync.param.yaml @@ -4,6 +4,7 @@ timeout_ms: 70.0 match_threshold_ms: 50.0 image_buffer_size: 15 + debug_mode: false filter_scope_minx: -100.0 filter_scope_miny: -100.0 filter_scope_minz: -100.0 diff --git a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml index c07c4a02884c2..4861b019be3fa 100644 --- a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml @@ -79,9 +79,6 @@ - - - diff --git a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml index 40374f2b8ab29..7785e0c889d11 100644 --- a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml @@ -65,9 +65,6 @@ - - - diff --git a/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml index 5c77b3a1f64d0..586f28701bab8 100644 --- a/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml @@ -68,9 +68,6 @@ - - - diff --git a/perception/image_projection_based_fusion/schema/roi_sync.schema.json b/perception/image_projection_based_fusion/schema/roi_sync.schema.json index 4df0193c65ebf..b6f2d46e18ebc 100644 --- a/perception/image_projection_based_fusion/schema/roi_sync.schema.json +++ b/perception/image_projection_based_fusion/schema/roi_sync.schema.json @@ -31,6 +31,11 @@ "default": 15, "minimum": 1 }, + "debug_mode": { + "type": "boolean", + "description": "Whether to debug or not.", + "default": false + }, "filter_scope_minx": { "type": "number", "description": "Minimum x position to be considered for debug [m].", From 3031e7223f808bfba23b4bd42e6c7e9d60e52246 Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Thu, 28 Sep 2023 14:36:10 +0900 Subject: [PATCH 08/12] refactor: rework parameters for `roi_pointcloud_fusion` Signed-off-by: ktro2828 --- .../config/roi_pointcloud_fusion.param.yaml | 5 +++ .../launch/roi_pointcloud_fusion.launch.xml | 8 +--- .../schema/roi_pointcloud_fusion.schema.json | 41 +++++++++++++++++++ 3 files changed, 48 insertions(+), 6 deletions(-) create mode 100644 perception/image_projection_based_fusion/config/roi_pointcloud_fusion.param.yaml create mode 100644 perception/image_projection_based_fusion/schema/roi_pointcloud_fusion.schema.json diff --git a/perception/image_projection_based_fusion/config/roi_pointcloud_fusion.param.yaml b/perception/image_projection_based_fusion/config/roi_pointcloud_fusion.param.yaml new file mode 100644 index 0000000000000..5b86b8e81d1aa --- /dev/null +++ b/perception/image_projection_based_fusion/config/roi_pointcloud_fusion.param.yaml @@ -0,0 +1,5 @@ +/**: + ros__parameters: + fuse_unknown_only: true + min_cluster_size: 2 + cluster_2d_tolerance: 0.5 diff --git a/perception/image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml index 181f4ccb88320..e20c342a14a0a 100644 --- a/perception/image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml @@ -1,8 +1,5 @@ - - - @@ -23,6 +20,7 @@ + @@ -38,9 +36,7 @@ - - - + diff --git a/perception/image_projection_based_fusion/schema/roi_pointcloud_fusion.schema.json b/perception/image_projection_based_fusion/schema/roi_pointcloud_fusion.schema.json new file mode 100644 index 0000000000000..f39ef257ea789 --- /dev/null +++ b/perception/image_projection_based_fusion/schema/roi_pointcloud_fusion.schema.json @@ -0,0 +1,41 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for RoI PointCloud Fusion Node", + "type": "object", + "definitions": { + "roi_pointcloud_fusion": { + "type": "object", + "properties": { + "fuse_unknown_only": { + "type": "boolean", + "description": "Whether to fuse only UNKNOWN clusters.", + "default": true + }, + "min_cluster_size": { + "type": "integer", + "description": "The minimum number of points that a cluster must contain to be considered as valid.", + "default": 2 + }, + "cluster_2d_tolerance": { + "type": "number", + "description": "A cluster tolerance measured in radial direction [m]", + "default": 0.5, + "exclusiveMinimum": 0.0 + } + }, + "required": ["fuse_unknown_only", "min_cluster_size", "cluster_2d_tolerance"] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/roi_pointcloud_fusion" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} From 0726f769a4b402cd92e394fc276756d22647c12a Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Thu, 28 Sep 2023 14:38:52 +0900 Subject: [PATCH 09/12] chore: update maintainers Signed-off-by: ktro2828 --- perception/image_projection_based_fusion/package.xml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/perception/image_projection_based_fusion/package.xml b/perception/image_projection_based_fusion/package.xml index 1648de210ec2c..49ff4dafc7900 100644 --- a/perception/image_projection_based_fusion/package.xml +++ b/perception/image_projection_based_fusion/package.xml @@ -9,6 +9,8 @@ Shunsuke Miura Yoshi Ri badai nguyen + Kotaro Uetake + Tao Zhong Apache License 2.0 ament_cmake_auto From af733b2929b39b92b3d08d55dd494b62617e141a Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Thu, 28 Sep 2023 14:44:05 +0900 Subject: [PATCH 10/12] refactor: remove debug_mode Signed-off-by: ktro2828 --- .../launch/pointpainting_fusion.launch.xml | 1 - .../launch/roi_cluster_fusion.launch.xml | 1 - .../launch/roi_detected_object_fusion.launch.xml | 1 - 3 files changed, 3 deletions(-) diff --git a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml index 4861b019be3fa..33781461fa1cc 100644 --- a/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/pointpainting_fusion.launch.xml @@ -30,7 +30,6 @@ - diff --git a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml index 7785e0c889d11..52dd71e9579c1 100644 --- a/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_cluster_fusion.launch.xml @@ -23,7 +23,6 @@ - diff --git a/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml index 586f28701bab8..c9da81af9ddb0 100644 --- a/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_detected_object_fusion.launch.xml @@ -25,7 +25,6 @@ - From 22c503d586eede96604007d77420e36854156f6e Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Wed, 11 Oct 2023 13:58:42 +0900 Subject: [PATCH 11/12] refactor: rename parameter to avoid failure of spell-check Signed-off-by: ktro2828 --- .../config/roi_sync.param.yaml | 12 ++++++------ .../schema/roi_sync.schema.json | 12 ++++++------ .../src/fusion_node.cpp | 12 ++++++------ 3 files changed, 18 insertions(+), 18 deletions(-) diff --git a/perception/image_projection_based_fusion/config/roi_sync.param.yaml b/perception/image_projection_based_fusion/config/roi_sync.param.yaml index f2e020344acb9..99d85089befb8 100644 --- a/perception/image_projection_based_fusion/config/roi_sync.param.yaml +++ b/perception/image_projection_based_fusion/config/roi_sync.param.yaml @@ -5,9 +5,9 @@ match_threshold_ms: 50.0 image_buffer_size: 15 debug_mode: false - filter_scope_minx: -100.0 - filter_scope_miny: -100.0 - filter_scope_minz: -100.0 - filter_scope_maxx: 100.0 - filter_scope_maxy: 100.0 - filter_scope_maxz: 100.0 + filter_scope_min_x: -100.0 + filter_scope_min_y: -100.0 + filter_scope_min_z: -100.0 + filter_scope_max_x: 100.0 + filter_scope_max_y: 100.0 + filter_scope_max_z: 100.0 diff --git a/perception/image_projection_based_fusion/schema/roi_sync.schema.json b/perception/image_projection_based_fusion/schema/roi_sync.schema.json index b6f2d46e18ebc..411fb678a49a7 100644 --- a/perception/image_projection_based_fusion/schema/roi_sync.schema.json +++ b/perception/image_projection_based_fusion/schema/roi_sync.schema.json @@ -36,32 +36,32 @@ "description": "Whether to debug or not.", "default": false }, - "filter_scope_minx": { + "filter_scope_min_x": { "type": "number", "description": "Minimum x position to be considered for debug [m].", "default": -100.0 }, - "filter_scope_miny": { + "filter_scope_min_y": { "type": "number", "description": "Minimum y position to be considered for debug [m].", "default": -100.0 }, - "filter_scope_minz": { + "filter_scope_min_z": { "type": "number", "description": "Minimum z position to be considered for debug [m].", "default": -100.0 }, - "filter_scope_maxx": { + "filter_scope_max_x": { "type": "number", "description": "Maximum x position to be considered for debug [m].", "default": 100.0 }, - "filter_scope_maxy": { + "filter_scope_max_y": { "type": "number", "description": "Maximum y position to be considered for debug [m].", "default": 100.0 }, - "filter_scope_maxz": { + "filter_scope_max_z": { "type": "number", "description": "Maximum z position [m].", "default": 100.0 diff --git a/perception/image_projection_based_fusion/src/fusion_node.cpp b/perception/image_projection_based_fusion/src/fusion_node.cpp index 3d1345f75752b..4abd92d7fb063 100644 --- a/perception/image_projection_based_fusion/src/fusion_node.cpp +++ b/perception/image_projection_based_fusion/src/fusion_node.cpp @@ -139,12 +139,12 @@ FusionNode::FusionNode( // cspell: ignore minx, maxx, miny, maxy, minz, maxz // FIXME: use min_x instead of minx - filter_scope_minx_ = declare_parameter("filter_scope_minx"); - filter_scope_maxx_ = declare_parameter("filter_scope_maxx"); - filter_scope_miny_ = declare_parameter("filter_scope_miny"); - filter_scope_maxy_ = declare_parameter("filter_scope_maxy"); - filter_scope_minz_ = declare_parameter("filter_scope_minz"); - filter_scope_maxz_ = declare_parameter("filter_scope_maxz"); + filter_scope_minx_ = declare_parameter("filter_scope_min_x"); + filter_scope_maxx_ = declare_parameter("filter_scope_max_x"); + filter_scope_miny_ = declare_parameter("filter_scope_min_y"); + filter_scope_maxy_ = declare_parameter("filter_scope_max_y"); + filter_scope_minz_ = declare_parameter("filter_scope_min_z"); + filter_scope_maxz_ = declare_parameter("filter_scope_max_z"); } template From 7b03f7475a43bf47bba9077eaeee357b7389efce Mon Sep 17 00:00:00 2001 From: ktro2828 Date: Fri, 8 Dec 2023 12:46:34 +0900 Subject: [PATCH 12/12] fix: fix typo and parameters for initialization Signed-off-by: ktro2828 --- .../config/pointpainting.param.yaml | 4 +++- .../launch/roi_pointcloud_fusion.launch.xml | 2 +- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/perception/image_projection_based_fusion/config/pointpainting.param.yaml b/perception/image_projection_based_fusion/config/pointpainting.param.yaml index 7ea5f53ac2b96..21d31f216373b 100755 --- a/perception/image_projection_based_fusion/config/pointpainting.param.yaml +++ b/perception/image_projection_based_fusion/config/pointpainting.param.yaml @@ -10,6 +10,7 @@ downsample_factor: 1 encoder_in_feature_size: 12 yaw_norm_thresholds: [0.3, 0.3, 0.3, 0.3, 0.0] + has_twist: false densification_params: world_frame_id: "map" num_past_frames: 0 @@ -19,6 +20,7 @@ iou_nms_target_class_names: ["CAR"] iou_nms_search_distance_2d: 10.0 iou_nms_threshold: 0.1 + score_threshold: 0.4 omp_params: # omp params - omp_num_threads: 1 + num_threads: 1 diff --git a/perception/image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml b/perception/image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml index e20c342a14a0a..046d88d06e2a1 100644 --- a/perception/image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml +++ b/perception/image_projection_based_fusion/launch/roi_pointcloud_fusion.launch.xml @@ -36,7 +36,7 @@ - +