Skip to content

Commit aabd7cd

Browse files
committed
Further improvements for the sanitization process
1 parent b85ee97 commit aabd7cd

File tree

1 file changed

+31
-28
lines changed

1 file changed

+31
-28
lines changed

perception/multi_object_tracker/src/multi_object_tracker_core.cpp

+31-28
Original file line numberDiff line numberDiff line change
@@ -386,13 +386,30 @@ 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(list_tracker.begin(), list_tracker.end());
392+
std::sort(sorted_list_tracker.begin(), sorted_list_tracker.end(),
393+
[](const std::shared_ptr<Tracker>& a, const std::shared_ptr<Tracker>& b) {
394+
bool a_unknown = (a->getHighestProbLabel() == Label::UNKNOWN);
395+
bool b_unknown = (b->getHighestProbLabel() == Label::UNKNOWN);
396+
if (a_unknown != b_unknown) {
397+
return b_unknown; // Put non-UNKNOWN objects first
398+
}
399+
return a->getTotalMeasurementCount() > b->getTotalMeasurementCount(); // Then sort by measurement count
400+
});
401+
389402
/* delete collision tracker */
390-
for (auto itr1 = list_tracker.begin(); itr1 != list_tracker.end(); ++itr1) {
403+
for (size_t i = 0; i < sorted_list_tracker.size(); ++i) {
404+
/* block erasing if no measurement */
405+
if (sorted_list_tracker[i]->getNoMeasurementCount() > 0) {
406+
continue;
407+
}
391408
autoware_auto_perception_msgs::msg::TrackedObject object1;
392-
(*itr1)->getTrackedObject(time, object1);
393-
for (auto itr2 = std::next(itr1); itr2 != list_tracker.end(); ++itr2) {
409+
sorted_list_tracker[i]->getTrackedObject(time, object1);
410+
for (size_t j = i + 1; j < sorted_list_tracker.size(); ++j) {
394411
autoware_auto_perception_msgs::msg::TrackedObject object2;
395-
(*itr2)->getTrackedObject(time, object2);
412+
sorted_list_tracker[j]->getTrackedObject(time, object2);
396413
const double distance = std::hypot(
397414
object1.kinematics.pose_with_covariance.pose.position.x -
398415
object2.kinematics.pose_with_covariance.pose.position.x,
@@ -404,44 +421,30 @@ void MultiObjectTracker::sanitizeTracker(
404421

405422
const double min_union_iou_area = 1e-2;
406423
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;
424+
const auto & label1 = sorted_list_tracker[i]->getHighestProbLabel();
425+
const auto & label2 = sorted_list_tracker[j]->getHighestProbLabel();
410426
bool should_delete_tracker2 = false;
411427

412428
// If at least one of them is UNKNOWN, delete the one with lower IOU. Because the UNKNOWN
413429
// objects are not reliable.
414430
if (label1 == Label::UNKNOWN || label2 == Label::UNKNOWN) {
415431
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) {
432+
if (label2 == Label::UNKNOWN) {
425433
should_delete_tracker2 = true;
426434
}
427435
}
428436
} else { // If neither is UNKNOWN, delete the one with lower IOU.
429437
if (min_iou < iou) {
430-
if ((*itr1)->getTotalMeasurementCount() < (*itr2)->getTotalMeasurementCount()) {
431-
should_delete_tracker1 = true;
432-
} else {
433-
should_delete_tracker2 = true;
434-
}
438+
should_delete_tracker2 = 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 (should_delete_tracker2) {
443+
// Remove from original list_tracker
444+
list_tracker.remove(sorted_list_tracker[j]);
445+
// Remove from sorted list
446+
sorted_list_tracker.erase(sorted_list_tracker.begin() + j);
447+
--j;
445448
}
446449
}
447450
}

0 commit comments

Comments
 (0)