@@ -456,13 +456,30 @@ void MultiObjectTracker::sanitizeTracker(
456
456
constexpr float min_iou = 0.1 ;
457
457
constexpr float min_iou_for_unknown_object = 0.001 ;
458
458
constexpr double distance_threshold = 5.0 ;
459
+
460
+ // Create sorted list with non-UNKNOWN objects first, then by measurement count
461
+ std::vector<std::shared_ptr<Tracker>> sorted_list_tracker (list_tracker.begin (), list_tracker.end ());
462
+ std::sort (sorted_list_tracker.begin (), sorted_list_tracker.end (),
463
+ [](const std::shared_ptr<Tracker>& a, const std::shared_ptr<Tracker>& b) {
464
+ bool a_unknown = (a->getHighestProbLabel () == Label::UNKNOWN);
465
+ bool b_unknown = (b->getHighestProbLabel () == Label::UNKNOWN);
466
+ if (a_unknown != b_unknown) {
467
+ return b_unknown; // Put non-UNKNOWN objects first
468
+ }
469
+ return a->getTotalMeasurementCount () > b->getTotalMeasurementCount (); // Then sort by measurement count
470
+ });
471
+
459
472
/* delete collision tracker */
460
- for (auto itr1 = list_tracker.begin (); itr1 != list_tracker.end (); ++itr1) {
473
+ for (size_t i = 0 ; i < sorted_list_tracker.size (); ++i) {
474
+ /* block erasing if no measurement */
475
+ if (sorted_list_tracker[i]->getNoMeasurementCount () > 0 ) {
476
+ continue ;
477
+ }
461
478
autoware_auto_perception_msgs::msg::TrackedObject object1;
462
- (*itr1) ->getTrackedObject (time , object1);
463
- for (auto itr2 = std::next (itr1); itr2 != list_tracker. end (); ++itr2 ) {
479
+ sorted_list_tracker[i] ->getTrackedObject (time , object1);
480
+ for (size_t j = i + 1 ; j < sorted_list_tracker. size (); ++j ) {
464
481
autoware_auto_perception_msgs::msg::TrackedObject object2;
465
- (*itr2) ->getTrackedObject (time , object2);
482
+ sorted_list_tracker[j] ->getTrackedObject (time , object2);
466
483
const double distance = std::hypot (
467
484
object1.kinematics .pose_with_covariance .pose .position .x -
468
485
object2.kinematics .pose_with_covariance .pose .position .x ,
@@ -474,48 +491,30 @@ void MultiObjectTracker::sanitizeTracker(
474
491
475
492
const double min_union_iou_area = 1e-2 ;
476
493
const auto iou = object_recognition_utils::get2dIoU (object1, object2, min_union_iou_area);
477
- const auto & label1 = (*itr1)->getHighestProbLabel ();
478
- const auto & label2 = (*itr2)->getHighestProbLabel ();
479
- bool should_delete_tracker1 = false ;
494
+ const auto & label1 = sorted_list_tracker[i]->getHighestProbLabel ();
495
+ const auto & label2 = sorted_list_tracker[j]->getHighestProbLabel ();
480
496
bool should_delete_tracker2 = false ;
481
497
482
498
// If at least one of them is UNKNOWN, delete the one with lower IOU. Because the UNKNOWN
483
499
// objects are not reliable.
484
500
if (label1 == Label::UNKNOWN || label2 == Label::UNKNOWN) {
485
501
if (min_iou_for_unknown_object < iou) {
486
- if (label1 == Label::UNKNOWN && label2 == Label::UNKNOWN) {
487
- if ((*itr1)->getTotalMeasurementCount () < (*itr2)->getTotalMeasurementCount ()) {
488
- should_delete_tracker1 = true ;
489
- } else {
490
- should_delete_tracker2 = true ;
491
- }
492
- } else if (label1 == Label::UNKNOWN) {
493
- if ((*itr2)->getNoMeasurementCount () <= 0 ) {
494
- should_delete_tracker1 = true ;
495
- }
496
- } else if (label2 == Label::UNKNOWN) {
497
- if ((*itr1)->getNoMeasurementCount () <= 0 ) {
498
- should_delete_tracker2 = true ;
499
- }
502
+ if (label2 == Label::UNKNOWN) {
503
+ should_delete_tracker2 = true ;
500
504
}
501
505
}
502
506
} else { // If neither is UNKNOWN, delete the one with lower IOU.
503
507
if (min_iou < iou) {
504
- if ((*itr1)->getTotalMeasurementCount () < (*itr2)->getTotalMeasurementCount ()) {
505
- should_delete_tracker1 = true ;
506
- } else {
507
- should_delete_tracker2 = true ;
508
- }
508
+ should_delete_tracker2 = true ;
509
509
}
510
510
}
511
511
512
- if (should_delete_tracker1) {
513
- itr1 = list_tracker.erase (itr1);
514
- --itr1;
515
- break ;
516
- } else if (should_delete_tracker2) {
517
- itr2 = list_tracker.erase (itr2);
518
- --itr2;
512
+ if (should_delete_tracker2) {
513
+ // Remove from original list_tracker
514
+ list_tracker.remove (sorted_list_tracker[j]);
515
+ // Remove from sorted list
516
+ sorted_list_tracker.erase (sorted_list_tracker.begin () + j);
517
+ --j;
519
518
}
520
519
}
521
520
}
0 commit comments