Skip to content

Commit 322d5a7

Browse files
committed
fix: update object size only by updating object size, do not memorize previous object size
Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>
1 parent a8a5ce1 commit 322d5a7

File tree

5 files changed

+9
-19
lines changed

5 files changed

+9
-19
lines changed

perception/multi_object_tracker/include/multi_object_tracker/tracker/model/big_vehicle_tracker.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,6 @@ class BigVehicleTracker : public Tracker
4949
double height;
5050
};
5151
BoundingBox bounding_box_;
52-
BoundingBox last_input_bounding_box_;
5352
Eigen::Vector2d tracking_offset_;
5453

5554
private:

perception/multi_object_tracker/include/multi_object_tracker/tracker/model/normal_vehicle_tracker.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,6 @@ class NormalVehicleTracker : public Tracker
4949
double height;
5050
};
5151
BoundingBox bounding_box_;
52-
BoundingBox last_input_bounding_box_;
5352
Eigen::Vector2d tracking_offset_;
5453

5554
private:

perception/multi_object_tracker/include/multi_object_tracker/utils/utils.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -280,7 +280,7 @@ inline void calcAnchorPointOffset(
280280

281281
// update offset
282282
const Eigen::Vector2d offset = calcOffsetVectorFromShapeChange(w_n - w, l_n - l, indx);
283-
tracking_offset += offset;
283+
tracking_offset = offset;
284284

285285
// offset input object
286286
const Eigen::Matrix2d R = Eigen::Rotation2Dd(yaw).toRotationMatrix();

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

+4-8
Original file line numberDiff line numberDiff line change
@@ -76,7 +76,6 @@ BigVehicleTracker::BigVehicleTracker(
7676
if (object.shape.type == autoware_perception_msgs::msg::Shape::BOUNDING_BOX) {
7777
bounding_box_ = {
7878
object.shape.dimensions.x, object.shape.dimensions.y, object.shape.dimensions.z};
79-
last_input_bounding_box_ = bounding_box_;
8079
} else {
8180
autoware_perception_msgs::msg::DetectedObject bbox_object;
8281
if (!utils::convertConvexHullToBoundingBox(object, bbox_object)) {
@@ -89,7 +88,6 @@ BigVehicleTracker::BigVehicleTracker(
8988
bbox_object.shape.dimensions.x, bbox_object.shape.dimensions.y,
9089
bbox_object.shape.dimensions.z};
9190
}
92-
last_input_bounding_box_ = bounding_box_;
9391
}
9492
// set maximum and minimum size
9593
constexpr double max_size = 30.0;
@@ -211,11 +209,11 @@ autoware_perception_msgs::msg::DetectedObject BigVehicleTracker::getUpdatingObje
211209
}
212210

213211
// get offset measurement
214-
int nearest_corner_index = utils::getNearestCornerOrSurface(
212+
const int nearest_corner_index = utils::getNearestCornerOrSurface(
215213
tracked_x, tracked_y, tracked_yaw, bounding_box_.width, bounding_box_.length, self_transform);
216214
utils::calcAnchorPointOffset(
217-
last_input_bounding_box_.width, last_input_bounding_box_.length, nearest_corner_index,
218-
bbox_object, tracked_yaw, updating_object, tracking_offset_);
215+
bounding_box_.width, bounding_box_.length, nearest_corner_index, bbox_object, tracked_yaw,
216+
updating_object, tracking_offset_);
219217

220218
// UNCERTAINTY MODEL
221219
if (!object.kinematics.has_position_covariance) {
@@ -329,15 +327,13 @@ bool BigVehicleTracker::measureWithShape(
329327
return false;
330328
}
331329

332-
constexpr double gain = 0.1;
330+
constexpr double gain = 0.5;
333331
constexpr double gain_inv = 1.0 - gain;
334332

335333
// update object size
336334
bounding_box_.length = gain_inv * bounding_box_.length + gain * object.shape.dimensions.x;
337335
bounding_box_.width = gain_inv * bounding_box_.width + gain * object.shape.dimensions.y;
338336
bounding_box_.height = gain_inv * bounding_box_.height + gain * object.shape.dimensions.z;
339-
last_input_bounding_box_ = {
340-
object.shape.dimensions.x, object.shape.dimensions.y, object.shape.dimensions.z};
341337

342338
// set maximum and minimum size
343339
constexpr double max_size = 30.0;

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

+4-8
Original file line numberDiff line numberDiff line change
@@ -76,7 +76,6 @@ NormalVehicleTracker::NormalVehicleTracker(
7676
if (object.shape.type == autoware_perception_msgs::msg::Shape::BOUNDING_BOX) {
7777
bounding_box_ = {
7878
object.shape.dimensions.x, object.shape.dimensions.y, object.shape.dimensions.z};
79-
last_input_bounding_box_ = bounding_box_;
8079
} else {
8180
autoware_perception_msgs::msg::DetectedObject bbox_object;
8281
if (!utils::convertConvexHullToBoundingBox(object, bbox_object)) {
@@ -90,7 +89,6 @@ NormalVehicleTracker::NormalVehicleTracker(
9089
bbox_object.shape.dimensions.x, bbox_object.shape.dimensions.y,
9190
bbox_object.shape.dimensions.z};
9291
}
93-
last_input_bounding_box_ = bounding_box_;
9492
}
9593
// set maximum and minimum size
9694
constexpr double max_size = 20.0;
@@ -213,11 +211,11 @@ autoware_perception_msgs::msg::DetectedObject NormalVehicleTracker::getUpdatingO
213211
}
214212

215213
// get offset measurement
216-
int nearest_corner_index = utils::getNearestCornerOrSurface(
214+
const int nearest_corner_index = utils::getNearestCornerOrSurface(
217215
tracked_x, tracked_y, tracked_yaw, bounding_box_.width, bounding_box_.length, self_transform);
218216
utils::calcAnchorPointOffset(
219-
last_input_bounding_box_.width, last_input_bounding_box_.length, nearest_corner_index,
220-
bbox_object, tracked_yaw, updating_object, tracking_offset_);
217+
bounding_box_.width, bounding_box_.length, nearest_corner_index, bbox_object, tracked_yaw,
218+
updating_object, tracking_offset_);
221219

222220
// UNCERTAINTY MODEL
223221
if (!object.kinematics.has_position_covariance) {
@@ -331,15 +329,13 @@ bool NormalVehicleTracker::measureWithShape(
331329
return false;
332330
}
333331

334-
constexpr double gain = 0.1;
332+
constexpr double gain = 0.5;
335333
constexpr double gain_inv = 1.0 - gain;
336334

337335
// update object size
338336
bounding_box_.length = gain_inv * bounding_box_.length + gain * object.shape.dimensions.x;
339337
bounding_box_.width = gain_inv * bounding_box_.width + gain * object.shape.dimensions.y;
340338
bounding_box_.height = gain_inv * bounding_box_.height + gain * object.shape.dimensions.z;
341-
last_input_bounding_box_ = {
342-
object.shape.dimensions.x, object.shape.dimensions.y, object.shape.dimensions.z};
343339

344340
// set maximum and minimum size
345341
constexpr double max_size = 20.0;

0 commit comments

Comments
 (0)