Skip to content

Commit 72adba3

Browse files
committed
fix: adjust minimum sizes to 0.3m
Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>
1 parent 09201ea commit 72adba3

File tree

4 files changed

+20
-20
lines changed

4 files changed

+20
-20
lines changed

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

+4-4
Original file line numberDiff line numberDiff line change
@@ -69,9 +69,9 @@ BicycleTracker::BicycleTracker(
6969
bounding_box_ = {1.0, 0.5, 1.7};
7070
}
7171
// set minimum size
72-
bounding_box_.length = std::max(bounding_box_.length, 0.5);
72+
bounding_box_.length = std::max(bounding_box_.length, 0.3);
7373
bounding_box_.width = std::max(bounding_box_.width, 0.3);
74-
bounding_box_.height = std::max(bounding_box_.height, 0.8);
74+
bounding_box_.height = std::max(bounding_box_.height, 0.3);
7575

7676
// Set motion model parameters
7777
{
@@ -236,9 +236,9 @@ bool BicycleTracker::measureWithShape(
236236
bounding_box_.width = gain_inv * bounding_box_.width + gain * object.shape.dimensions.y;
237237
bounding_box_.height = gain_inv * bounding_box_.height + gain * object.shape.dimensions.z;
238238
// set minimum size
239-
bounding_box_.length = std::max(bounding_box_.length, 0.5);
239+
bounding_box_.length = std::max(bounding_box_.length, 0.3);
240240
bounding_box_.width = std::max(bounding_box_.width, 0.3);
241-
bounding_box_.height = std::max(bounding_box_.height, 0.8);
241+
bounding_box_.height = std::max(bounding_box_.height, 0.3);
242242

243243
// update motion model
244244
motion_model_.updateExtendedState(bounding_box_.length);

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

+6-6
Original file line numberDiff line numberDiff line change
@@ -83,9 +83,9 @@ BigVehicleTracker::BigVehicleTracker(
8383
last_input_bounding_box_ = bounding_box_;
8484
}
8585
// set minimum size
86-
bounding_box_.length = std::max(bounding_box_.length, 2.5);
87-
bounding_box_.width = std::max(bounding_box_.width, 1.0);
88-
bounding_box_.height = std::max(bounding_box_.height, 1.0);
86+
bounding_box_.length = std::max(bounding_box_.length, 0.3);
87+
bounding_box_.width = std::max(bounding_box_.width, 0.3);
88+
bounding_box_.height = std::max(bounding_box_.height, 0.3);
8989

9090
// Set motion model parameters
9191
{
@@ -313,9 +313,9 @@ bool BigVehicleTracker::measureWithShape(
313313
last_input_bounding_box_ = {
314314
object.shape.dimensions.x, object.shape.dimensions.y, object.shape.dimensions.z};
315315
// set minimum size
316-
bounding_box_.length = std::max(bounding_box_.length, 2.5);
317-
bounding_box_.width = std::max(bounding_box_.width, 1.0);
318-
bounding_box_.height = std::max(bounding_box_.height, 1.0);
316+
bounding_box_.length = std::max(bounding_box_.length, 0.3);
317+
bounding_box_.width = std::max(bounding_box_.width, 0.3);
318+
bounding_box_.height = std::max(bounding_box_.height, 0.3);
319319

320320
// update motion model
321321
motion_model_.updateExtendedState(bounding_box_.length);

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

+6-6
Original file line numberDiff line numberDiff line change
@@ -83,9 +83,9 @@ NormalVehicleTracker::NormalVehicleTracker(
8383
last_input_bounding_box_ = bounding_box_;
8484
}
8585
// set minimum size
86-
bounding_box_.length = std::max(bounding_box_.length, 1.5);
87-
bounding_box_.width = std::max(bounding_box_.width, 0.5);
88-
bounding_box_.height = std::max(bounding_box_.height, 1.0);
86+
bounding_box_.length = std::max(bounding_box_.length, 0.3);
87+
bounding_box_.width = std::max(bounding_box_.width, 0.3);
88+
bounding_box_.height = std::max(bounding_box_.height, 0.3);
8989

9090
// Set motion model parameters
9191
{
@@ -313,9 +313,9 @@ bool NormalVehicleTracker::measureWithShape(
313313
last_input_bounding_box_ = {
314314
object.shape.dimensions.x, object.shape.dimensions.y, object.shape.dimensions.z};
315315
// set minimum size
316-
bounding_box_.length = std::max(bounding_box_.length, 1.5);
317-
bounding_box_.width = std::max(bounding_box_.width, 0.5);
318-
bounding_box_.height = std::max(bounding_box_.height, 1.0);
316+
bounding_box_.length = std::max(bounding_box_.length, 0.3);
317+
bounding_box_.width = std::max(bounding_box_.width, 0.3);
318+
bounding_box_.height = std::max(bounding_box_.height, 0.3);
319319

320320
// update motion model
321321
motion_model_.updateExtendedState(bounding_box_.length);

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

+4-4
Original file line numberDiff line numberDiff line change
@@ -73,9 +73,9 @@ PedestrianTracker::PedestrianTracker(
7373
// set minimum size
7474
bounding_box_.length = std::max(bounding_box_.length, 0.3);
7575
bounding_box_.width = std::max(bounding_box_.width, 0.3);
76-
bounding_box_.height = std::max(bounding_box_.height, 0.8);
76+
bounding_box_.height = std::max(bounding_box_.height, 0.3);
7777
cylinder_.width = std::max(cylinder_.width, 0.3);
78-
cylinder_.height = std::max(cylinder_.height, 0.8);
78+
cylinder_.height = std::max(cylinder_.height, 0.3);
7979

8080
// Set motion model parameters
8181
{
@@ -219,9 +219,9 @@ bool PedestrianTracker::measureWithShape(
219219
// set minimum size
220220
bounding_box_.length = std::max(bounding_box_.length, 0.3);
221221
bounding_box_.width = std::max(bounding_box_.width, 0.3);
222-
bounding_box_.height = std::max(bounding_box_.height, 0.8);
222+
bounding_box_.height = std::max(bounding_box_.height, 0.3);
223223
cylinder_.width = std::max(cylinder_.width, 0.3);
224-
cylinder_.height = std::max(cylinder_.height, 0.8);
224+
cylinder_.height = std::max(cylinder_.height, 0.3);
225225

226226
return true;
227227
}

0 commit comments

Comments
 (0)