Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(object_merger): preserve unknown objects close to known objects #4499

Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion perception/object_merger/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ The successive shortest path algorithm is used to solve the data association pro
| `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/tier4/autoware_auto_msgs/blob/tier4/main/autoware_auto_perception_msgs/msg/ObjectClassification.idl). |
| `generalized_iou_threshold` | double | Generalized IoU threshold |
| `generalized_iou_threshold` | `std::vector<double>` | Generalized IoU threshold for each class |

## Tips

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ class ObjectAssociationMergerNode : public rclcpp::Node
{
double precision_threshold;
double recall_threshold;
double generalized_iou_threshold;
std::map<int, double> generalized_iou_threshold;
std::map<int /*class label*/, double /*distance_threshold*/> distance_threshold_map;
} overlapped_judge_param_;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
<param from="$(var data_association_matrix_path)"/>
<param from="$(var distance_threshold_list_path)"/>
<param name="priority_mode" value="$(var priority_mode)"/>
<param name="generalized_iou_threshold" value="-0.6"/>
<param name="precision_threshold_to_judge_overlapped" value="0.4"/>
<param name="remove_overlapped_unknown_objects" value="true"/>
</node>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,11 @@
const autoware_auto_perception_msgs::msg::DetectedObject & unknown_object,
const autoware_auto_perception_msgs::msg::DetectedObject & known_object,
const double precision_threshold, const double recall_threshold,
std::map<int, double> distance_threshold_map, const double generalized_iou_threshold)
std::map<int, double> distance_threshold_map,
const std::map<int, double> generalized_iou_threshold_map)
{
const double generalized_iou_threshold = generalized_iou_threshold_map.at(
object_recognition_utils::getHighestProbLabel(known_object.classification));

Check warning on line 42 in perception/object_merger/src/object_association_merger/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/object_merger/src/object_association_merger/node.cpp#L41-L42

Added lines #L41 - L42 were not covered by tests
const double distance_threshold = distance_threshold_map.at(
object_recognition_utils::getHighestProbLabel(known_object.classification));
const double sq_distance_threshold = std::pow(distance_threshold, 2.0);
Expand Down Expand Up @@ -95,7 +98,7 @@
overlapped_judge_param_.recall_threshold =
declare_parameter<double>("recall_threshold_to_judge_overlapped", 0.5);
overlapped_judge_param_.generalized_iou_threshold =
declare_parameter<double>("generalized_iou_threshold");
convertListToClassMap(declare_parameter<std::vector<double>>("generalized_iou_threshold"));

Check warning on line 101 in perception/object_merger/src/object_association_merger/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/object_merger/src/object_association_merger/node.cpp#L101

Added line #L101 was not covered by tests

// get distance_threshold_map from distance_threshold_list
/** TODO(Shin-kyoto):
Expand Down
Loading