Skip to content

Commit

Permalink
fix(object_merger): preserve unknown objects close to known objects (a…
Browse files Browse the repository at this point in the history
…utowarefoundation#4499)

* fix(object_merger): separate GIoU

Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>

* fix: update GIoU threshold

Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>

---------

Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>
  • Loading branch information
badai-nguyen committed Aug 3, 2023
1 parent 010ed7e commit ec451cb
Show file tree
Hide file tree
Showing 5 changed files with 11 additions and 5 deletions.
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
3 changes: 3 additions & 0 deletions perception/object_merger/config/overlapped_judge.param.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -3,3 +3,6 @@
distance_threshold_list:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN
[9.0, 9.0, 9.0, 9.0, 9.0, 9.0, 9.0, 9.0] #UNKNOWN

generalized_iou_threshold:
[-0.1, -0.1, -0.1, -0.6, -0.6, -0.1, -0.1, -0.1]
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 @@ bool isUnknownObjectOverlapped(
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));
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 @@ ObjectAssociationMergerNode::ObjectAssociationMergerNode(const rclcpp::NodeOptio
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"));

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

0 comments on commit ec451cb

Please sign in to comment.