Skip to content

Commit b7fdccc

Browse files
authored
fix(multi_object_tracker): object size becomes zero, risk of numeric error and overflow on IoU calculation (#6597)
* fix: set object minimum size limits Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * fix: object shape conversion, from cylinder to bbox Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * fix: adjust minimum sizes to 0.3 m The minimum size is unified to a small number (0.3 m) to avoid side-effect of tracking. Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> --------- Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>
1 parent 4747e74 commit b7fdccc

File tree

4 files changed

+52
-3
lines changed

4 files changed

+52
-3
lines changed

perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp

+18-3
Original file line numberDiff line numberDiff line change
@@ -140,6 +140,11 @@ BicycleTracker::BicycleTracker(
140140
} else {
141141
bounding_box_ = {1.0, 0.5, 1.7};
142142
}
143+
// set minimum size
144+
bounding_box_.length = std::max(bounding_box_.length, 0.3);
145+
bounding_box_.width = std::max(bounding_box_.width, 0.3);
146+
bounding_box_.height = std::max(bounding_box_.height, 0.3);
147+
143148
ekf_.init(X, P);
144149

145150
// Set lf, lr
@@ -400,10 +405,15 @@ bool BicycleTracker::measureWithShape(
400405
{
401406
// if the input shape is convex type, convert it to bbox type
402407
autoware_auto_perception_msgs::msg::DetectedObject bbox_object;
403-
if (object.shape.type != autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) {
404-
utils::convertConvexHullToBoundingBox(object, bbox_object);
405-
} else {
408+
if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) {
406409
bbox_object = object;
410+
} else if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::CYLINDER) {
411+
// convert cylinder to bbox
412+
bbox_object.shape.dimensions.x = object.shape.dimensions.x;
413+
bbox_object.shape.dimensions.y = object.shape.dimensions.x;
414+
bbox_object.shape.dimensions.z = object.shape.dimensions.z;
415+
} else {
416+
utils::convertConvexHullToBoundingBox(object, bbox_object);
407417
}
408418

409419
constexpr float gain = 0.9;
@@ -415,6 +425,11 @@ bool BicycleTracker::measureWithShape(
415425
last_input_bounding_box_ = {
416426
bbox_object.shape.dimensions.x, bbox_object.shape.dimensions.y, bbox_object.shape.dimensions.z};
417427

428+
// set minimum size
429+
bounding_box_.length = std::max(bounding_box_.length, 0.3);
430+
bounding_box_.width = std::max(bounding_box_.width, 0.3);
431+
bounding_box_.height = std::max(bounding_box_.height, 0.3);
432+
418433
// update lf, lr
419434
lf_ = std::max(bounding_box_.length * 0.3, 0.3); // 30% front from the center, minimum of 0.3m
420435
lr_ = std::max(bounding_box_.length * 0.3, 0.3); // 30% rear from the center, minimum of 0.3m

perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp

+10
Original file line numberDiff line numberDiff line change
@@ -157,6 +157,11 @@ BigVehicleTracker::BigVehicleTracker(
157157
/* calc nearest corner index*/
158158
setNearestCornerOrSurfaceIndex(self_transform); // this index is used in next measure step
159159

160+
// set minimum size
161+
bounding_box_.length = std::max(bounding_box_.length, 0.3);
162+
bounding_box_.width = std::max(bounding_box_.width, 0.3);
163+
bounding_box_.height = std::max(bounding_box_.height, 0.3);
164+
160165
// Set lf, lr
161166
lf_ = std::max(bounding_box_.length * 0.3, 1.5); // 30% front from the center, minimum of 1.5m
162167
lr_ = std::max(bounding_box_.length * 0.25, 1.5); // 25% rear from the center, minimum of 1.5m
@@ -455,6 +460,11 @@ bool BigVehicleTracker::measureWithShape(
455460
last_input_bounding_box_ = {
456461
bbox_object.shape.dimensions.x, bbox_object.shape.dimensions.y, bbox_object.shape.dimensions.z};
457462

463+
// set minimum size
464+
bounding_box_.length = std::max(bounding_box_.length, 0.3);
465+
bounding_box_.width = std::max(bounding_box_.width, 0.3);
466+
bounding_box_.height = std::max(bounding_box_.height, 0.3);
467+
458468
// update lf, lr
459469
lf_ = std::max(bounding_box_.length * 0.3, 1.5); // 30% front from the center, minimum of 1.5m
460470
lr_ = std::max(bounding_box_.length * 0.25, 1.5); // 25% rear from the center, minimum of 1.5m

perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp

+10
Original file line numberDiff line numberDiff line change
@@ -157,6 +157,11 @@ NormalVehicleTracker::NormalVehicleTracker(
157157
/* calc nearest corner index*/
158158
setNearestCornerOrSurfaceIndex(self_transform); // this index is used in next measure step
159159

160+
// set minimum size
161+
bounding_box_.length = std::max(bounding_box_.length, 0.3);
162+
bounding_box_.width = std::max(bounding_box_.width, 0.3);
163+
bounding_box_.height = std::max(bounding_box_.height, 0.3);
164+
160165
// Set lf, lr
161166
lf_ = std::max(bounding_box_.length * 0.3, 1.0); // 30% front from the center, minimum of 1.0m
162167
lr_ = std::max(bounding_box_.length * 0.25, 1.0); // 25% rear from the center, minimum of 1.0m
@@ -455,6 +460,11 @@ bool NormalVehicleTracker::measureWithShape(
455460
last_input_bounding_box_ = {
456461
bbox_object.shape.dimensions.x, bbox_object.shape.dimensions.y, bbox_object.shape.dimensions.z};
457462

463+
// set minimum size
464+
bounding_box_.length = std::max(bounding_box_.length, 0.3);
465+
bounding_box_.width = std::max(bounding_box_.width, 0.3);
466+
bounding_box_.height = std::max(bounding_box_.height, 0.3);
467+
458468
// update lf, lr
459469
lf_ = std::max(bounding_box_.length * 0.3, 1.0); // 30% front from the center, minimum of 1.0m
460470
lr_ = std::max(bounding_box_.length * 0.25, 1.0); // 25% rear from the center, minimum of 1.0m

perception/multi_object_tracker/src/tracker/model/pedestrian_tracker.cpp

+14
Original file line numberDiff line numberDiff line change
@@ -143,6 +143,13 @@ PedestrianTracker::PedestrianTracker(
143143
cylinder_ = {object.shape.dimensions.x, object.shape.dimensions.z};
144144
}
145145

146+
// set minimum size
147+
bounding_box_.length = std::max(bounding_box_.length, 0.3);
148+
bounding_box_.width = std::max(bounding_box_.width, 0.3);
149+
bounding_box_.height = std::max(bounding_box_.height, 0.3);
150+
cylinder_.width = std::max(cylinder_.width, 0.3);
151+
cylinder_.height = std::max(cylinder_.height, 0.3);
152+
146153
ekf_.init(X, P);
147154
}
148155

@@ -317,6 +324,13 @@ bool PedestrianTracker::measureWithShape(
317324
return false;
318325
}
319326

327+
// set minimum size
328+
bounding_box_.length = std::max(bounding_box_.length, 0.3);
329+
bounding_box_.width = std::max(bounding_box_.width, 0.3);
330+
bounding_box_.height = std::max(bounding_box_.height, 0.3);
331+
cylinder_.width = std::max(cylinder_.width, 0.3);
332+
cylinder_.height = std::max(cylinder_.height, 0.3);
333+
320334
return true;
321335
}
322336

0 commit comments

Comments
 (0)