Skip to content

Commit 156b114

Browse files
mebasogluarmaganarsln
authored andcommitted
fix(multi_object_tracker): make sure smallest unknown footprint is 0.3
Signed-off-by: Mehmet Emin BAŞOĞLU <mehmeteminbasoglu@hotmail.com>
1 parent 52b2fd6 commit 156b114

File tree

2 files changed

+18
-2
lines changed

2 files changed

+18
-2
lines changed

perception/multi_object_tracker/src/data_association/data_association.cpp

+9-2
Original file line numberDiff line numberDiff line change
@@ -159,7 +159,7 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix(
159159

160160
for (size_t measurement_idx = 0; measurement_idx < measurements.objects.size();
161161
++measurement_idx) {
162-
const autoware_auto_perception_msgs::msg::DetectedObject & measurement_object =
162+
autoware_auto_perception_msgs::msg::DetectedObject measurement_object =
163163
measurements.objects.at(measurement_idx);
164164
const std::uint8_t measurement_label =
165165
object_recognition_utils::getHighestProbLabel(measurement_object.classification);
@@ -180,10 +180,10 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix(
180180
if (max_dist < dist) passed_gate = false;
181181
}
182182
// area gate
183+
const double area = tier4_autoware_utils::getArea(measurement_object.shape);
183184
if (passed_gate) {
184185
const double max_area = max_area_matrix_(tracker_label, measurement_label);
185186
const double min_area = min_area_matrix_(tracker_label, measurement_label);
186-
const double area = tier4_autoware_utils::getArea(measurement_object.shape);
187187
if (area < min_area || max_area < area) passed_gate = false;
188188
}
189189
// angle gate
@@ -207,6 +207,13 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix(
207207
if (passed_gate) {
208208
const double min_iou = min_iou_matrix_(tracker_label, measurement_label);
209209
const double min_union_iou_area = 1e-2;
210+
if (
211+
measurement_object.shape.type == autoware_auto_perception_msgs::msg::Shape::POLYGON &&
212+
area == 0 && measurement_object.shape.footprint.points.size() == 1) {
213+
measurement_object.shape.footprint.points.front().x = 0.3;
214+
measurement_object.shape.footprint.points.front().y = 0.3;
215+
measurement_object.shape.footprint.points.front().z = 0.3;
216+
}
210217
const double iou = object_recognition_utils::get2dIoU(
211218
measurement_object, tracked_object, min_union_iou_area);
212219
if (iou < min_iou) passed_gate = false;

perception/multi_object_tracker/src/multi_object_tracker_core.cpp

+9
Original file line numberDiff line numberDiff line change
@@ -387,6 +387,15 @@ void MultiObjectTracker::sanitizeTracker(
387387
continue;
388388
}
389389

390+
if (
391+
object1.shape.type == autoware_auto_perception_msgs::msg::Shape::POLYGON &&
392+
tier4_autoware_utils::getArea(object1.shape) == 0 &&
393+
object1.shape.footprint.points.size() == 1) {
394+
object1.shape.footprint.points.front().x = 0.3;
395+
object1.shape.footprint.points.front().y = 0.3;
396+
object1.shape.footprint.points.front().z = 0.3;
397+
}
398+
390399
const double min_union_iou_area = 1e-2;
391400
const auto iou = object_recognition_utils::get2dIoU(object1, object2, min_union_iou_area);
392401
const auto & label1 = (*itr1)->getHighestProbLabel();

0 commit comments

Comments
 (0)