Skip to content

Commit 60ed979

Browse files
authored
Merge pull request #1907 from tier4/feat/v0.19.1/multi-tracker-sanitize-update
Feat/v0.19.1/multi tracker sanitize update
2 parents b85ee97 + a716512 commit 60ed979

File tree

1 file changed

+38
-30
lines changed

1 file changed

+38
-30
lines changed

perception/multi_object_tracker/src/multi_object_tracker_core.cpp

+38-30
Original file line numberDiff line numberDiff line change
@@ -386,13 +386,29 @@ void MultiObjectTracker::sanitizeTracker(
386386
constexpr float min_iou = 0.1;
387387
constexpr float min_iou_for_unknown_object = 0.001;
388388
constexpr double distance_threshold = 5.0;
389+
390+
// Create sorted list with non-UNKNOWN objects first, then by measurement count
391+
std::vector<std::shared_ptr<Tracker>> sorted_list_tracker(
392+
list_tracker.begin(), list_tracker.end());
393+
std::sort(
394+
sorted_list_tracker.begin(), sorted_list_tracker.end(),
395+
[](const std::shared_ptr<Tracker> & a, const std::shared_ptr<Tracker> & b) {
396+
bool a_unknown = (a->getHighestProbLabel() == Label::UNKNOWN);
397+
bool b_unknown = (b->getHighestProbLabel() == Label::UNKNOWN);
398+
if (a_unknown != b_unknown) {
399+
return b_unknown; // Put non-UNKNOWN objects first
400+
}
401+
return a->getTotalMeasurementCount() >
402+
b->getTotalMeasurementCount(); // Then sort by measurement count
403+
});
404+
389405
/* delete collision tracker */
390-
for (auto itr1 = list_tracker.begin(); itr1 != list_tracker.end(); ++itr1) {
406+
for (size_t i = 0; i < sorted_list_tracker.size(); ++i) {
391407
autoware_auto_perception_msgs::msg::TrackedObject object1;
392-
(*itr1)->getTrackedObject(time, object1);
393-
for (auto itr2 = std::next(itr1); itr2 != list_tracker.end(); ++itr2) {
408+
sorted_list_tracker[i]->getTrackedObject(time, object1);
409+
for (size_t j = i + 1; j < sorted_list_tracker.size(); ++j) {
394410
autoware_auto_perception_msgs::msg::TrackedObject object2;
395-
(*itr2)->getTrackedObject(time, object2);
411+
sorted_list_tracker[j]->getTrackedObject(time, object2);
396412
const double distance = std::hypot(
397413
object1.kinematics.pose_with_covariance.pose.position.x -
398414
object2.kinematics.pose_with_covariance.pose.position.x,
@@ -404,44 +420,36 @@ void MultiObjectTracker::sanitizeTracker(
404420

405421
const double min_union_iou_area = 1e-2;
406422
const auto iou = object_recognition_utils::get2dIoU(object1, object2, min_union_iou_area);
407-
const auto & label1 = (*itr1)->getHighestProbLabel();
408-
const auto & label2 = (*itr2)->getHighestProbLabel();
409-
bool should_delete_tracker1 = false;
410-
bool should_delete_tracker2 = false;
423+
const auto & label1 = sorted_list_tracker[i]->getHighestProbLabel();
424+
const auto & label2 = sorted_list_tracker[j]->getHighestProbLabel();
425+
bool delete_candidate_tracker = false;
411426

412427
// If at least one of them is UNKNOWN, delete the one with lower IOU. Because the UNKNOWN
413428
// objects are not reliable.
414429
if (label1 == Label::UNKNOWN || label2 == Label::UNKNOWN) {
415430
if (min_iou_for_unknown_object < iou) {
416-
if (label1 == Label::UNKNOWN && label2 == Label::UNKNOWN) {
417-
if ((*itr1)->getTotalMeasurementCount() < (*itr2)->getTotalMeasurementCount()) {
418-
should_delete_tracker1 = true;
419-
} else {
420-
should_delete_tracker2 = true;
421-
}
422-
} else if (label1 == Label::UNKNOWN) {
423-
should_delete_tracker1 = true;
424-
} else if (label2 == Label::UNKNOWN) {
425-
should_delete_tracker2 = true;
431+
if (label2 == Label::UNKNOWN) {
432+
delete_candidate_tracker = true;
426433
}
427434
}
428435
} else { // If neither is UNKNOWN, delete the one with lower IOU.
429436
if (min_iou < iou) {
430-
if ((*itr1)->getTotalMeasurementCount() < (*itr2)->getTotalMeasurementCount()) {
431-
should_delete_tracker1 = true;
432-
} else {
433-
should_delete_tracker2 = true;
434-
}
437+
/* erase only when prioritized one has a measurement */
438+
delete_candidate_tracker = true;
435439
}
436440
}
437441

438-
if (should_delete_tracker1) {
439-
itr1 = list_tracker.erase(itr1);
440-
--itr1;
441-
break;
442-
} else if (should_delete_tracker2) {
443-
itr2 = list_tracker.erase(itr2);
444-
--itr2;
442+
if (delete_candidate_tracker) {
443+
/* erase only when prioritized one has later(or equal time) meas than the other's */
444+
if (
445+
sorted_list_tracker[i]->getElapsedTimeFromLastUpdate(time) <=
446+
sorted_list_tracker[j]->getElapsedTimeFromLastUpdate(time)) {
447+
// Remove from original list_tracker
448+
list_tracker.remove(sorted_list_tracker[j]);
449+
// Remove from sorted list
450+
sorted_list_tracker.erase(sorted_list_tracker.begin() + j);
451+
--j;
452+
}
445453
}
446454
}
447455
}

0 commit comments

Comments
 (0)