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_route_handler): fix bugprone-exception-escape #9738

Merged
merged 2 commits into from
Dec 24, 2024
Merged
Changes from 1 commit
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
96 changes: 56 additions & 40 deletions planning/autoware_route_handler/src/route_handler.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021-2024 TIER IV, Inc.

Check notice on line 1 in planning/autoware_route_handler/src/route_handler.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Lines of Code in a Single File

The lines of code increases from 1723 to 1739, improve code health by reducing it to 1000. The number of Lines of Code in a single file. More Lines of Code lowers the code health.

Check notice on line 1 in planning/autoware_route_handler/src/route_handler.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 4.82 to 4.86, 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 @@ -1163,32 +1163,40 @@
const bool & invert_opposite) const noexcept
{
lanelet::ConstLanelets linestring_shared;
auto lanelet_at_left = getLeftLanelet(lane);
auto lanelet_at_left_opposite = getLeftOppositeLanelets(lane);
while (lanelet_at_left) {
linestring_shared.push_back(lanelet_at_left.value());
lanelet_at_left = getLeftLanelet(lanelet_at_left.value());
if (!lanelet_at_left) {
break;
try {
auto lanelet_at_left = getLeftLanelet(lane);
auto lanelet_at_left_opposite = getLeftOppositeLanelets(lane);
while (lanelet_at_left) {
linestring_shared.push_back(lanelet_at_left.value());
lanelet_at_left = getLeftLanelet(lanelet_at_left.value());
if (!lanelet_at_left) {
break;
}
lanelet_at_left_opposite = getLeftOppositeLanelets(lanelet_at_left.value());
}
lanelet_at_left_opposite = getLeftOppositeLanelets(lanelet_at_left.value());
}

if (!lanelet_at_left_opposite.empty() && include_opposite) {
if (invert_opposite) {
linestring_shared.push_back(lanelet_at_left_opposite.front().invert());
} else {
linestring_shared.push_back(lanelet_at_left_opposite.front());
}
auto lanelet_at_right = getRightLanelet(lanelet_at_left_opposite.front());
while (lanelet_at_right) {
if (!lanelet_at_left_opposite.empty() && include_opposite) {
if (invert_opposite) {
linestring_shared.push_back(lanelet_at_right.value().invert());
linestring_shared.push_back(lanelet_at_left_opposite.front().invert());
} else {
linestring_shared.push_back(lanelet_at_right.value());
linestring_shared.push_back(lanelet_at_left_opposite.front());
}
auto lanelet_at_right = getRightLanelet(lanelet_at_left_opposite.front());
while (lanelet_at_right) {
if (invert_opposite) {
linestring_shared.push_back(lanelet_at_right.value().invert());
} else {
linestring_shared.push_back(lanelet_at_right.value());
}
lanelet_at_right = getRightLanelet(lanelet_at_right.value());
}
lanelet_at_right = getRightLanelet(lanelet_at_right.value());
}
} catch (const std::exception & e) {
std::cerr << "Exception in getAllLeftSharedLinestringLanelets: " << e.what() << std::endl;
return {};
} catch (...) {

Check warning on line 1197 in planning/autoware_route_handler/src/route_handler.cpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_route_handler/src/route_handler.cpp#L1195-L1197

Added lines #L1195 - L1197 were not covered by tests
std::cerr << "Unknown exception in getAllLeftSharedLinestringLanelets" << std::endl;
return {};

Check warning on line 1199 in planning/autoware_route_handler/src/route_handler.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

RouteHandler::getAllLeftSharedLinestringLanelets has a cyclomatic complexity of 10, threshold = 9. 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 1199 in planning/autoware_route_handler/src/route_handler.cpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_route_handler/src/route_handler.cpp#L1199

Added line #L1199 was not covered by tests
}
return linestring_shared;
}
Expand All @@ -1198,32 +1206,40 @@
const bool & invert_opposite) const noexcept
{
lanelet::ConstLanelets linestring_shared;
auto lanelet_at_right = getRightLanelet(lane);
auto lanelet_at_right_opposite = getRightOppositeLanelets(lane);
while (lanelet_at_right) {
linestring_shared.push_back(lanelet_at_right.value());
lanelet_at_right = getRightLanelet(lanelet_at_right.value());
if (!lanelet_at_right) {
break;
try {
auto lanelet_at_right = getRightLanelet(lane);
auto lanelet_at_right_opposite = getRightOppositeLanelets(lane);
while (lanelet_at_right) {
linestring_shared.push_back(lanelet_at_right.value());
lanelet_at_right = getRightLanelet(lanelet_at_right.value());
if (!lanelet_at_right) {
break;
}
lanelet_at_right_opposite = getRightOppositeLanelets(lanelet_at_right.value());
}
lanelet_at_right_opposite = getRightOppositeLanelets(lanelet_at_right.value());
}

if (!lanelet_at_right_opposite.empty() && include_opposite) {
if (invert_opposite) {
linestring_shared.push_back(lanelet_at_right_opposite.front().invert());
} else {
linestring_shared.push_back(lanelet_at_right_opposite.front());
}
auto lanelet_at_left = getLeftLanelet(lanelet_at_right_opposite.front());
while (lanelet_at_left) {
if (!lanelet_at_right_opposite.empty() && include_opposite) {
if (invert_opposite) {
linestring_shared.push_back(lanelet_at_left.value().invert());
linestring_shared.push_back(lanelet_at_right_opposite.front().invert());
} else {
linestring_shared.push_back(lanelet_at_left.value());
linestring_shared.push_back(lanelet_at_right_opposite.front());
}
auto lanelet_at_left = getLeftLanelet(lanelet_at_right_opposite.front());
while (lanelet_at_left) {
if (invert_opposite) {
linestring_shared.push_back(lanelet_at_left.value().invert());
} else {
linestring_shared.push_back(lanelet_at_left.value());
}
lanelet_at_left = getLeftLanelet(lanelet_at_left.value());
}
lanelet_at_left = getLeftLanelet(lanelet_at_left.value());
}
} catch (const std::exception & e) {
std::cerr << "Exception in getAllRightSharedLinestringLanelets: " << e.what() << std::endl;
return {};
} catch (...) {

Check warning on line 1240 in planning/autoware_route_handler/src/route_handler.cpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_route_handler/src/route_handler.cpp#L1238-L1240

Added lines #L1238 - L1240 were not covered by tests
std::cerr << "Unknown exception in getAllRightSharedLinestringLanelets" << std::endl;
return {};

Check warning on line 1242 in planning/autoware_route_handler/src/route_handler.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Method

RouteHandler::getAllRightSharedLinestringLanelets has a cyclomatic complexity of 10, threshold = 9. 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 1242 in planning/autoware_route_handler/src/route_handler.cpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_route_handler/src/route_handler.cpp#L1242

Added line #L1242 was not covered by tests
}
return linestring_shared;
}
Expand Down
Loading