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

feat(perception_utils): enable tracker to track smaller object by adapting min_union_area #2303

Merged
Show file tree
Hide file tree
Changes from all commits
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
5 changes: 3 additions & 2 deletions common/perception_utils/include/perception_utils/matching.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ inline double getUnionArea(const Polygon2d & source_polygon, const Polygon2d & t
}

template <class T1, class T2>
double get2dIoU(const T1 source_object, const T2 target_object)
double get2dIoU(const T1 source_object, const T2 target_object, const double min_union_area = 0.01)
{
const auto source_polygon = tier4_autoware_utils::toPolygon2d(source_object);
const auto target_polygon = tier4_autoware_utils::toPolygon2d(target_object);
Expand All @@ -72,7 +72,8 @@ double get2dIoU(const T1 source_object, const T2 target_object)
if (intersection_area == 0.0) return 0.0;
const double union_area = getUnionArea(source_polygon, target_polygon);

const double iou = union_area < 0.01 ? 0.0 : std::min(1.0, intersection_area / union_area);
const double iou =
union_area < min_union_area ? 0.0 : std::min(1.0, intersection_area / union_area);
return iou;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -206,7 +206,9 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix(
// 2d iou gate
if (passed_gate) {
const double min_iou = min_iou_matrix_(tracker_label, measurement_label);
const double iou = perception_utils::get2dIoU(measurement_object, tracked_object);
const double min_union_iou_area = 1e-2;
const double iou =
perception_utils::get2dIoU(measurement_object, tracked_object, min_union_iou_area);
if (iou < min_iou) passed_gate = false;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -262,7 +262,8 @@ void MultiObjectTracker::sanitizeTracker(
continue;
}

const auto iou = perception_utils::get2dIoU(object1, object2);
const double min_union_iou_area = 1e-2;
const auto iou = perception_utils::get2dIoU(object1, object2, min_union_iou_area);
const auto & label1 = (*itr1)->getHighestProbLabel();
const auto & label2 = (*itr2)->getHighestProbLabel();
bool should_delete_tracker1 = false;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -154,7 +154,8 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix(
// 2d iou gate
if (passed_gate) {
const double min_iou = min_iou_matrix_(object1_label, object0_label);
const double iou = perception_utils::get2dIoU(object0, object1);
const double min_union_iou_area = 1e-2;
const double iou = perception_utils::get2dIoU(object0, object1, min_union_iou_area);
if (iou < min_iou) passed_gate = false;
}

Expand Down