From 223443b9834ab62d75a895427ebe87a9528fe081 Mon Sep 17 00:00:00 2001 From: Taekjin LEE Date: Tue, 12 Mar 2024 16:57:05 +0900 Subject: [PATCH] fix: adjust minimum sizes to 0.3m --- .../src/tracker/model/bicycle_tracker.cpp | 8 ++++---- .../src/tracker/model/big_vehicle_tracker.cpp | 12 ++++++------ .../src/tracker/model/normal_vehicle_tracker.cpp | 12 ++++++------ .../src/tracker/model/pedestrian_tracker.cpp | 8 ++++---- 4 files changed, 20 insertions(+), 20 deletions(-) diff --git a/perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp index 1ed8ab2812a32..7b7927fdc1edb 100644 --- a/perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp +++ b/perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp @@ -69,9 +69,9 @@ BicycleTracker::BicycleTracker( bounding_box_ = {1.0, 0.5, 1.7}; } // set minimum size - bounding_box_.length = std::max(bounding_box_.length, 0.5); + bounding_box_.length = std::max(bounding_box_.length, 0.3); bounding_box_.width = std::max(bounding_box_.width, 0.3); - bounding_box_.height = std::max(bounding_box_.height, 0.8); + bounding_box_.height = std::max(bounding_box_.height, 0.3); // Set motion model parameters { @@ -236,9 +236,9 @@ bool BicycleTracker::measureWithShape( bounding_box_.width = gain_inv * bounding_box_.width + gain * object.shape.dimensions.y; bounding_box_.height = gain_inv * bounding_box_.height + gain * object.shape.dimensions.z; // set minimum size - bounding_box_.length = std::max(bounding_box_.length, 0.5); + bounding_box_.length = std::max(bounding_box_.length, 0.3); bounding_box_.width = std::max(bounding_box_.width, 0.3); - bounding_box_.height = std::max(bounding_box_.height, 0.8); + bounding_box_.height = std::max(bounding_box_.height, 0.3); // update motion model motion_model_.updateExtendedState(bounding_box_.length); diff --git a/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp index 30cbe733d0824..421729753d419 100644 --- a/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp +++ b/perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp @@ -83,9 +83,9 @@ BigVehicleTracker::BigVehicleTracker( last_input_bounding_box_ = bounding_box_; } // set minimum size - bounding_box_.length = std::max(bounding_box_.length, 2.5); - bounding_box_.width = std::max(bounding_box_.width, 1.0); - bounding_box_.height = std::max(bounding_box_.height, 1.0); + bounding_box_.length = std::max(bounding_box_.length, 0.3); + bounding_box_.width = std::max(bounding_box_.width, 0.3); + bounding_box_.height = std::max(bounding_box_.height, 0.3); // Set motion model parameters { @@ -313,9 +313,9 @@ bool BigVehicleTracker::measureWithShape( last_input_bounding_box_ = { object.shape.dimensions.x, object.shape.dimensions.y, object.shape.dimensions.z}; // set minimum size - bounding_box_.length = std::max(bounding_box_.length, 2.5); - bounding_box_.width = std::max(bounding_box_.width, 1.0); - bounding_box_.height = std::max(bounding_box_.height, 1.0); + bounding_box_.length = std::max(bounding_box_.length, 0.3); + bounding_box_.width = std::max(bounding_box_.width, 0.3); + bounding_box_.height = std::max(bounding_box_.height, 0.3); // update motion model motion_model_.updateExtendedState(bounding_box_.length); diff --git a/perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp index b87e759e27bc3..04532270ece10 100644 --- a/perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp +++ b/perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp @@ -83,9 +83,9 @@ NormalVehicleTracker::NormalVehicleTracker( last_input_bounding_box_ = bounding_box_; } // set minimum size - bounding_box_.length = std::max(bounding_box_.length, 1.5); - bounding_box_.width = std::max(bounding_box_.width, 0.5); - bounding_box_.height = std::max(bounding_box_.height, 1.0); + bounding_box_.length = std::max(bounding_box_.length, 0.3); + bounding_box_.width = std::max(bounding_box_.width, 0.3); + bounding_box_.height = std::max(bounding_box_.height, 0.3); // Set motion model parameters { @@ -313,9 +313,9 @@ bool NormalVehicleTracker::measureWithShape( last_input_bounding_box_ = { object.shape.dimensions.x, object.shape.dimensions.y, object.shape.dimensions.z}; // set minimum size - bounding_box_.length = std::max(bounding_box_.length, 1.5); - bounding_box_.width = std::max(bounding_box_.width, 0.5); - bounding_box_.height = std::max(bounding_box_.height, 1.0); + bounding_box_.length = std::max(bounding_box_.length, 0.3); + bounding_box_.width = std::max(bounding_box_.width, 0.3); + bounding_box_.height = std::max(bounding_box_.height, 0.3); // update motion model motion_model_.updateExtendedState(bounding_box_.length); diff --git a/perception/multi_object_tracker/src/tracker/model/pedestrian_tracker.cpp b/perception/multi_object_tracker/src/tracker/model/pedestrian_tracker.cpp index 3ac45d239cd37..e01558c75761c 100644 --- a/perception/multi_object_tracker/src/tracker/model/pedestrian_tracker.cpp +++ b/perception/multi_object_tracker/src/tracker/model/pedestrian_tracker.cpp @@ -73,9 +73,9 @@ PedestrianTracker::PedestrianTracker( // set minimum size bounding_box_.length = std::max(bounding_box_.length, 0.3); bounding_box_.width = std::max(bounding_box_.width, 0.3); - bounding_box_.height = std::max(bounding_box_.height, 0.8); + bounding_box_.height = std::max(bounding_box_.height, 0.3); cylinder_.width = std::max(cylinder_.width, 0.3); - cylinder_.height = std::max(cylinder_.height, 0.8); + cylinder_.height = std::max(cylinder_.height, 0.3); // Set motion model parameters { @@ -219,9 +219,9 @@ bool PedestrianTracker::measureWithShape( // set minimum size bounding_box_.length = std::max(bounding_box_.length, 0.3); bounding_box_.width = std::max(bounding_box_.width, 0.3); - bounding_box_.height = std::max(bounding_box_.height, 0.8); + bounding_box_.height = std::max(bounding_box_.height, 0.3); cylinder_.width = std::max(cylinder_.width, 0.3); - cylinder_.height = std::max(cylinder_.height, 0.8); + cylinder_.height = std::max(cylinder_.height, 0.3); return true; }