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

feat(blind_spot): consider road_shoulder if exist #7925

Merged
merged 1 commit into from
Jul 10, 2024
Merged
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
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 planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.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.60 to 4.72, 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 @@ -621,57 +621,76 @@
for (const auto i : lane_ids) {
const auto lane = lanelet_map_ptr->laneletLayer.get(i);
const auto ego_half_lanelet = generateHalfLanelet(lane);
const auto adj =
const auto assoc_adj =
turn_direction_ == TurnDirection::LEFT
? (routing_graph_ptr->adjacentLeft(lane))
: (turn_direction_ == TurnDirection::RIGHT ? (routing_graph_ptr->adjacentRight(lane))
: boost::none);
const std::optional<lanelet::ConstLanelet> opposite_adj =
[&]() -> std::optional<lanelet::ConstLanelet> {
if (!!adj) {
if (!!assoc_adj) {
return std::nullopt;
}
if (turn_direction_ == TurnDirection::LEFT) {
// this should exist in right-hand traffic
const auto adjacent_lanes =
lanelet_map_ptr->laneletLayer.findUsages(lane.leftBound().invert());
if (adjacent_lanes.empty()) {
return std::nullopt;
}
return adjacent_lanes.front();
}
if (turn_direction_ == TurnDirection::RIGHT) {
// this should exist in left-hand traffic
const auto adjacent_lanes =
lanelet_map_ptr->laneletLayer.findUsages(lane.rightBound().invert());
if (adjacent_lanes.empty()) {
return std::nullopt;
}
return adjacent_lanes.front();
} else {
return std::nullopt;
}
}();

if (!adj && !opposite_adj) {
blind_spot_lanelets.push_back(ego_half_lanelet);
} else if (!!adj) {
const auto adj_half_lanelet = generateExtendedAdjacentLanelet(adj.value(), turn_direction_);
const auto assoc_shoulder = [&]() -> std::optional<lanelet::ConstLanelet> {
if (turn_direction_ == TurnDirection::LEFT) {
return planner_data_->route_handler_->getLeftShoulderLanelet(lane);
} else if (turn_direction_ == TurnDirection::RIGHT) {
return planner_data_->route_handler_->getRightShoulderLanelet(lane);
}
return std::nullopt;
}();
if (assoc_shoulder) {
const auto lefts = (turn_direction_ == TurnDirection::LEFT)
? assoc_shoulder.value().leftBound()
: ego_half_lanelet.leftBound();
const auto rights = (turn_direction_ == TurnDirection::LEFT)
? ego_half_lanelet.rightBound()
: assoc_shoulder.value().rightBound();
blind_spot_lanelets.push_back(
lanelet::ConstLanelet(lanelet::InvalId, removeConst(lefts), removeConst(rights)));

} else if (!!assoc_adj) {
const auto adj_half_lanelet =
generateExtendedAdjacentLanelet(assoc_adj.value(), turn_direction_);
const auto lefts = (turn_direction_ == TurnDirection::LEFT) ? adj_half_lanelet.leftBound()
: ego_half_lanelet.leftBound();
const auto rights = (turn_direction_ == TurnDirection::RIGHT) ? adj_half_lanelet.rightBound()
: ego_half_lanelet.rightBound();
blind_spot_lanelets.push_back(
lanelet::ConstLanelet(lanelet::InvalId, removeConst(lefts), removeConst(rights)));
} else if (opposite_adj) {
const auto adj_half_lanelet =
generateExtendedOppositeAdjacentLanelet(opposite_adj.value(), turn_direction_);
const auto lefts = (turn_direction_ == TurnDirection::LEFT) ? adj_half_lanelet.leftBound()
: ego_half_lanelet.leftBound();
const auto rights = (turn_direction_ == TurnDirection::LEFT) ? ego_half_lanelet.rightBound()
: adj_half_lanelet.rightBound();
blind_spot_lanelets.push_back(
lanelet::ConstLanelet(lanelet::InvalId, removeConst(lefts), removeConst(rights)));
} else {
blind_spot_lanelets.push_back(ego_half_lanelet);

Check warning on line 693 in planning/behavior_velocity_planner/autoware_behavior_velocity_blind_spot_module/src/scene.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

BlindSpotModule::generateBlindSpotLanelets increases in cyclomatic complexity from 22 to 25, 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.
}
}
return blind_spot_lanelets;
Expand Down
Loading