Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(multi_object_tracker): object size becomes zero, risk of numeric error and overflow on IoU calculation #6597

Merged
Show file tree
Hide file tree
Changes from 3 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 Tier IV, Inc.

Check notice on line 1 in perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Overall Code Complexity

The mean cyclomatic complexity increases from 5.29 to 5.43, threshold = 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -140,6 +140,11 @@
} else {
bounding_box_ = {1.0, 0.5, 1.7};
}
// set minimum size
bounding_box_.length = std::max(bounding_box_.length, 0.5);
bounding_box_.width = std::max(bounding_box_.width, 0.3);
bounding_box_.height = std::max(bounding_box_.height, 0.8);

Check warning on line 146 in perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp

View check run for this annotation

Codecov / codecov/patch

perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp#L144-L146

Added lines #L144 - L146 were not covered by tests

Check warning on line 147 in perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

BicycleTracker::BicycleTracker increases from 89 to 92 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
ekf_.init(X, P);

// Set lf, lr
Expand Down Expand Up @@ -400,10 +405,15 @@
{
// if the input shape is convex type, convert it to bbox type
autoware_auto_perception_msgs::msg::DetectedObject bbox_object;
if (object.shape.type != autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) {
utils::convertConvexHullToBoundingBox(object, bbox_object);
} else {
if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::BOUNDING_BOX) {

Check warning on line 408 in perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp

View check run for this annotation

Codecov / codecov/patch

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

Added line #L408 was not covered by tests
bbox_object = object;
} else if (object.shape.type == autoware_auto_perception_msgs::msg::Shape::CYLINDER) {

Check warning on line 410 in perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp

View check run for this annotation

Codecov / codecov/patch

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

Added line #L410 was not covered by tests
// convert cylinder to bbox
bbox_object.shape.dimensions.x = object.shape.dimensions.x;
bbox_object.shape.dimensions.y = object.shape.dimensions.x;
bbox_object.shape.dimensions.z = object.shape.dimensions.z;

Check warning on line 414 in perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp

View check run for this annotation

Codecov / codecov/patch

perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp#L412-L414

Added lines #L412 - L414 were not covered by tests
} else {
utils::convertConvexHullToBoundingBox(object, bbox_object);

Check warning on line 416 in perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp

View check run for this annotation

Codecov / codecov/patch

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

Added line #L416 was not covered by tests
}

constexpr float gain = 0.9;
Expand All @@ -415,6 +425,11 @@
last_input_bounding_box_ = {
bbox_object.shape.dimensions.x, bbox_object.shape.dimensions.y, bbox_object.shape.dimensions.z};

// set minimum size
bounding_box_.length = std::max(bounding_box_.length, 0.5);
bounding_box_.width = std::max(bounding_box_.width, 0.3);
bounding_box_.height = std::max(bounding_box_.height, 0.8);

Check warning on line 431 in perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp

View check run for this annotation

Codecov / codecov/patch

perception/multi_object_tracker/src/tracker/model/bicycle_tracker.cpp#L429-L431

Added lines #L429 - L431 were not covered by tests

// update lf, lr
lf_ = std::max(bounding_box_.length * 0.3, 0.3); // 30% front from the center, minimum of 0.3m
lr_ = std::max(bounding_box_.length * 0.3, 0.3); // 30% rear from the center, minimum of 0.3m
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -157,6 +157,11 @@
/* calc nearest corner index*/
setNearestCornerOrSurfaceIndex(self_transform); // this index is used in next measure step

// 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);

Check warning on line 163 in perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp

View check run for this annotation

Codecov / codecov/patch

perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp#L161-L163

Added lines #L161 - L163 were not covered by tests

Check warning on line 164 in perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

BigVehicleTracker::BigVehicleTracker increases from 100 to 103 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
// Set lf, lr
lf_ = std::max(bounding_box_.length * 0.3, 1.5); // 30% front from the center, minimum of 1.5m
lr_ = std::max(bounding_box_.length * 0.25, 1.5); // 25% rear from the center, minimum of 1.5m
Expand Down Expand Up @@ -455,6 +460,11 @@
last_input_bounding_box_ = {
bbox_object.shape.dimensions.x, bbox_object.shape.dimensions.y, bbox_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);

Check warning on line 466 in perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp

View check run for this annotation

Codecov / codecov/patch

perception/multi_object_tracker/src/tracker/model/big_vehicle_tracker.cpp#L464-L466

Added lines #L464 - L466 were not covered by tests

// update lf, lr
lf_ = std::max(bounding_box_.length * 0.3, 1.5); // 30% front from the center, minimum of 1.5m
lr_ = std::max(bounding_box_.length * 0.25, 1.5); // 25% rear from the center, minimum of 1.5m
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -157,6 +157,11 @@
/* calc nearest corner index*/
setNearestCornerOrSurfaceIndex(self_transform); // this index is used in next measure step

// 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);

Check warning on line 163 in perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp

View check run for this annotation

Codecov / codecov/patch

perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp#L161-L163

Added lines #L161 - L163 were not covered by tests

Check warning on line 164 in perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

NormalVehicleTracker::NormalVehicleTracker increases from 100 to 103 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
// Set lf, lr
lf_ = std::max(bounding_box_.length * 0.3, 1.0); // 30% front from the center, minimum of 1.0m
lr_ = std::max(bounding_box_.length * 0.25, 1.0); // 25% rear from the center, minimum of 1.0m
Expand Down Expand Up @@ -455,6 +460,11 @@
last_input_bounding_box_ = {
bbox_object.shape.dimensions.x, bbox_object.shape.dimensions.y, bbox_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);

Check warning on line 466 in perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp

View check run for this annotation

Codecov / codecov/patch

perception/multi_object_tracker/src/tracker/model/normal_vehicle_tracker.cpp#L464-L466

Added lines #L464 - L466 were not covered by tests

// update lf, lr
lf_ = std::max(bounding_box_.length * 0.3, 1.0); // 30% front from the center, minimum of 1.0m
lr_ = std::max(bounding_box_.length * 0.25, 1.0); // 25% rear from the center, minimum of 1.0m
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -143,6 +143,13 @@
cylinder_ = {object.shape.dimensions.x, object.shape.dimensions.z};
}

// 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);
cylinder_.width = std::max(cylinder_.width, 0.3);
cylinder_.height = std::max(cylinder_.height, 0.8);

Check warning on line 151 in perception/multi_object_tracker/src/tracker/model/pedestrian_tracker.cpp

View check run for this annotation

Codecov / codecov/patch

perception/multi_object_tracker/src/tracker/model/pedestrian_tracker.cpp#L147-L151

Added lines #L147 - L151 were not covered by tests

Check warning on line 152 in perception/multi_object_tracker/src/tracker/model/pedestrian_tracker.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

PedestrianTracker::PedestrianTracker increases from 89 to 94 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
ekf_.init(X, P);
}

Expand Down Expand Up @@ -317,6 +324,13 @@
return false;
}

// 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);
cylinder_.width = std::max(cylinder_.width, 0.3);
cylinder_.height = std::max(cylinder_.height, 0.8);

Check warning on line 332 in perception/multi_object_tracker/src/tracker/model/pedestrian_tracker.cpp

View check run for this annotation

Codecov / codecov/patch

perception/multi_object_tracker/src/tracker/model/pedestrian_tracker.cpp#L328-L332

Added lines #L328 - L332 were not covered by tests

return true;
}

Expand Down
Loading