Skip to content

Commit

Permalink
refactor(object_merger): rework parameters (autowarefoundation#7337)
Browse files Browse the repository at this point in the history
* Deleted the default values in the source code, updated .param.yaml files, created schema.json files, updated readme.

Signed-off-by: Boyang <tby@udel.edu>

* style(pre-commit): autofix

---------

Signed-off-by: Boyang <tby@udel.edu>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
tby-udel and pre-commit-ci[bot] authored Jun 27, 2024
1 parent e96334c commit 23eb56d
Show file tree
Hide file tree
Showing 6 changed files with 142 additions and 17 deletions.
13 changes: 3 additions & 10 deletions perception/object_merger/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -25,16 +25,9 @@ The successive shortest path algorithm is used to solve the data association pro

## Parameters

| Name | Type | Description |
| --------------------------- | --------------------- | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| `can_assign_matrix` | double | Assignment table for data association |
| `max_dist_matrix` | double | Maximum distance table for data association |
| `max_area_matrix` | double | Maximum area table for data association |
| `min_area_matrix` | double | Minimum area table for data association |
| `max_rad_matrix` | double | Maximum angle table for data association |
| `base_link_frame_id` | double | association frame |
| `distance_threshold_list` | `std::vector<double>` | Distance threshold for each class used in judging overlap. The class order depends on [ObjectClassification](https://github.com/autowarefoundation/autoware_msgs/blob/main/autoware_perception_msgs/msg/ObjectClassification.msg). |
| `generalized_iou_threshold` | `std::vector<double>` | Generalized IoU threshold for each class |
{{ json_to_markdown("perception/object_merger/schema/object_association_merger.schema.json") }}
{{ json_to_markdown("perception/object_merger/schema/data_association_matrix.schema.json") }}
{{ json_to_markdown("perception/object_merger/schema/overlapped_judge.schema.json") }}

## Tips

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,4 +2,7 @@
ros__parameters:
sync_queue_size: 20
precision_threshold_to_judge_overlapped: 0.4
recall_threshold_to_judge_overlapped: 0.5
remove_overlapped_unknown_objects: true
base_link_frame_id: base_link
priority_mode: 3 # PriorityMode::Confidence
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Data Association Matrix Parameters",
"type": "object",
"properties": {
"ros__parameters": {
"type": "object",
"properties": {
"can_assign_matrix": {
"type": "array",
"items": {
"type": "number"
},
"description": "Assignment table for data association"
},
"max_dist_matrix": {
"type": "array",
"items": {
"type": "number"
},
"description": "Maximum distance table for data association"
},
"max_rad_matrix": {
"type": "array",
"items": {
"type": "number"
},
"description": "Maximum angle table for data association. If value is greater than pi, it will be ignored."
},
"min_iou_matrix": {
"type": "array",
"items": {
"type": "number"
},
"description": "Minimum IoU threshold matrix for data association. If value is negative, it will be ignored."
}
},
"required": ["can_assign_matrix", "max_dist_matrix", "max_rad_matrix", "min_iou_matrix"]
}
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for Object Association Merger Node",
"type": "object",
"definitions": {
"object_association_merger": {
"type": "object",
"properties": {
"sync_queue_size": {
"type": "integer",
"description": "The size of the synchronization queue.",
"default": 20
},
"precision_threshold_to_judge_overlapped": {
"type": "number",
"description": "The precision threshold to judge if objects are overlapped.",
"default": 0.4
},
"recall_threshold_to_judge_overlapped": {
"type": "number",
"description": "The recall threshold to judge if objects are overlapped.",
"default": 0.5
},
"remove_overlapped_unknown_objects": {
"type": "boolean",
"description": "Flag to remove overlapped unknown objects.",
"default": true
},
"base_link_frame_id": {
"type": "string",
"description": "The frame ID of the association frame.",
"default": "base_link"
},
"priority_mode": {
"type": "integer",
"description": "Index for the priority_mode.",
"default": 3,
"enum": [0, 1, 2, 3]
}
},
"required": [
"sync_queue_size",
"precision_threshold_to_judge_overlapped",
"recall_threshold_to_judge_overlapped",
"remove_overlapped_unknown_objects",
"base_link_frame_id",
"priority_mode"
]
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/object_association_merger"
}
},
"required": ["ros__parameters"]
}
},
"required": ["/**"]
}
27 changes: 27 additions & 0 deletions perception/object_merger/schema/overlapped_judge.schema.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Overlapped Judge Parameters",
"type": "object",
"properties": {
"ros__parameters": {
"type": "object",
"properties": {
"distance_threshold_list": {
"type": "array",
"items": {
"type": "number"
},
"description": "Distance threshold for each class used in judging overlap."
},
"generalized_iou_threshold": {
"type": "array",
"items": {
"type": "number"
},
"description": "Generalized IoU threshold for each class."
}
},
"required": ["distance_threshold_list", "generalized_iou_threshold"]
}
}
}
12 changes: 5 additions & 7 deletions perception/object_merger/src/object_association_merger/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,16 +80,14 @@ ObjectAssociationMergerNode::ObjectAssociationMergerNode(const rclcpp::NodeOptio
object1_sub_(this, "input/object1", rclcpp::QoS{1}.get_rmw_qos_profile())
{
// Parameters
base_link_frame_id_ = declare_parameter<std::string>("base_link_frame_id", "base_link");
priority_mode_ = static_cast<PriorityMode>(
declare_parameter<int>("priority_mode", static_cast<int>(PriorityMode::Confidence)));
sync_queue_size_ = declare_parameter<int>("sync_queue_size", 20);
remove_overlapped_unknown_objects_ =
declare_parameter<bool>("remove_overlapped_unknown_objects", true);
base_link_frame_id_ = declare_parameter<std::string>("base_link_frame_id");
priority_mode_ = static_cast<PriorityMode>(declare_parameter<int>("priority_mode"));
sync_queue_size_ = declare_parameter<int>("sync_queue_size");
remove_overlapped_unknown_objects_ = declare_parameter<bool>("remove_overlapped_unknown_objects");
overlapped_judge_param_.precision_threshold =
declare_parameter<double>("precision_threshold_to_judge_overlapped");
overlapped_judge_param_.recall_threshold =
declare_parameter<double>("recall_threshold_to_judge_overlapped", 0.5);
declare_parameter<double>("recall_threshold_to_judge_overlapped");
overlapped_judge_param_.generalized_iou_threshold =
convertListToClassMap(declare_parameter<std::vector<double>>("generalized_iou_threshold"));

Expand Down

0 comments on commit 23eb56d

Please sign in to comment.