Skip to content

Commit

Permalink
fix: bugprone-error
Browse files Browse the repository at this point in the history
Signed-off-by: kobayu858 <[email protected]>
  • Loading branch information
kobayu858 committed Dec 23, 2024
1 parent a88e90e commit 0f708e9
Showing 1 changed file with 56 additions and 40 deletions.
96 changes: 56 additions & 40 deletions planning/autoware_route_handler/src/route_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1163,32 +1163,40 @@ lanelet::ConstLanelets RouteHandler::getAllLeftSharedLinestringLanelets(
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 @@ lanelet::ConstLanelets RouteHandler::getAllRightSharedLinestringLanelets(
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

0 comments on commit 0f708e9

Please sign in to comment.