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(autoware_tensorrt_common): fix bugprone-integer-division #9660

Open
wants to merge 1 commit into
base: main
Choose a base branch
from
Open
Changes from all 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
16 changes: 10 additions & 6 deletions perception/autoware_tensorrt_common/src/tensorrt_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -311,12 +311,13 @@
int groups = conv->getNbGroups();
int stride = s_dims.d[0];
int num_weights = (dim_in.d[1] / groups) * dim_out.d[1] * k_dims.d[0] * k_dims.d[1];
float gflops = (2 * num_weights) * (dim_in.d[3] / stride * dim_in.d[2] / stride / 1e9);
;
float gflops = (2.0 * num_weights) * (static_cast<float>(dim_in.d[3]) / stride *
static_cast<float>(dim_in.d[2]) / stride / 1e9);

Check warning on line 315 in perception/autoware_tensorrt_common/src/tensorrt_common.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_tensorrt_common/src/tensorrt_common.cpp#L314-L315

Added lines #L314 - L315 were not covered by tests
total_gflops += gflops;
total_params += num_weights;
std::cout << "L" << i << " [conv " << k_dims.d[0] << "x" << k_dims.d[1] << " (" << groups
<< ") " << "/" << s_dims.d[0] << "] " << dim_in.d[3] << "x" << dim_in.d[2] << "x"
<< ") "
<< "/" << s_dims.d[0] << "] " << dim_in.d[3] << "x" << dim_in.d[2] << "x"
<< dim_in.d[1] << " -> " << dim_out.d[3] << "x" << dim_out.d[2] << "x"
<< dim_out.d[1];
std::cout << " weights:" << num_weights;
Expand All @@ -336,8 +337,10 @@
} else if (p_type == nvinfer1::PoolingType::kMAX_AVERAGE_BLEND) {
std::cout << "max avg blend ";
}
float gflops = dim_in.d[1] * dim_window.d[0] / dim_stride.d[0] * dim_window.d[1] /
dim_stride.d[1] * dim_in.d[2] * dim_in.d[3] / 1e9;
float gflops = static_cast<float>(dim_in.d[1]) *
(static_cast<float>(dim_window.d[0]) / static_cast<float>(dim_stride.d[0])) *
(static_cast<float>(dim_window.d[1]) / static_cast<float>(dim_stride.d[1])) *
static_cast<float>(dim_in.d[2]) * static_cast<float>(dim_in.d[3]) / 1e9;

Check warning on line 343 in perception/autoware_tensorrt_common/src/tensorrt_common.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

TrtCommon::printNetworkInfo already has high cyclomatic complexity, and now it increases in Lines of Code from 94 to 97. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.

Check warning on line 343 in perception/autoware_tensorrt_common/src/tensorrt_common.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_tensorrt_common/src/tensorrt_common.cpp#L340-L343

Added lines #L340 - L343 were not covered by tests
total_gflops += gflops;
std::cout << "pool " << dim_window.d[0] << "x" << dim_window.d[1] << "]";
std::cout << " GFLOPs:" << gflops;
Expand Down Expand Up @@ -381,7 +384,8 @@
if (num_available_dla > 0) {
std::cout << "###" << num_available_dla << " DLAs are supported! ###" << std::endl;
} else {
std::cout << "###Warning : " << "No DLA is supported! ###" << std::endl;
std::cout << "###Warning : "
<< "No DLA is supported! ###" << std::endl;

Check warning on line 388 in perception/autoware_tensorrt_common/src/tensorrt_common.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

TrtCommon::buildEngineFromOnnx already has high cyclomatic complexity, and now it increases in Lines of Code from 172 to 173. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
}
config->setDefaultDeviceType(nvinfer1::DeviceType::kDLA);
config->setDLACore(build_config_->dla_core_id);
Expand Down
Loading