@@ -159,7 +159,7 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix(
159
159
160
160
for (size_t measurement_idx = 0 ; measurement_idx < measurements.objects .size ();
161
161
++measurement_idx) {
162
- const autoware_auto_perception_msgs::msg::DetectedObject & measurement_object =
162
+ autoware_auto_perception_msgs::msg::DetectedObject measurement_object =
163
163
measurements.objects .at (measurement_idx);
164
164
const std::uint8_t measurement_label =
165
165
object_recognition_utils::getHighestProbLabel (measurement_object.classification );
@@ -180,10 +180,10 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix(
180
180
if (max_dist < dist) passed_gate = false ;
181
181
}
182
182
// area gate
183
+ const double area = tier4_autoware_utils::getArea (measurement_object.shape );
183
184
if (passed_gate) {
184
185
const double max_area = max_area_matrix_ (tracker_label, measurement_label);
185
186
const double min_area = min_area_matrix_ (tracker_label, measurement_label);
186
- const double area = tier4_autoware_utils::getArea (measurement_object.shape );
187
187
if (area < min_area || max_area < area) passed_gate = false ;
188
188
}
189
189
// angle gate
@@ -207,6 +207,13 @@ Eigen::MatrixXd DataAssociation::calcScoreMatrix(
207
207
if (passed_gate) {
208
208
const double min_iou = min_iou_matrix_ (tracker_label, measurement_label);
209
209
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
+ }
210
217
const double iou = object_recognition_utils::get2dIoU (
211
218
measurement_object, tracked_object, min_union_iou_area);
212
219
if (iou < min_iou) passed_gate = false ;
0 commit comments