Skip to content

fix(goal_planner): invert lane boundary of neighbor opposite lanelets when generating departure check lane #10207

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

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
Expand Up @@ -709,33 +709,38 @@
const lanelet::ConstLanelets & pull_over_lanes, const route_handler::RouteHandler & route_handler,
const bool left_side_parking)
{
const auto getBoundPoints =
[&](const lanelet::ConstLanelet & lane, const bool is_outer) -> lanelet::Points3d {
const auto getBoundPoints = [&](

Check warning on line 712 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp#L712

Added line #L712 was not covered by tests
const lanelet::ConstLanelet & lane, const bool is_outer,
const bool invert) -> lanelet::Points3d {
lanelet::Points3d points;
const auto & bound = left_side_parking ? (is_outer ? lane.leftBound() : lane.rightBound())
: (is_outer ? lane.rightBound() : lane.leftBound());
for (const auto & pt : bound) {
const auto ego_oriented_bound = invert ? bound.invert() : bound;
for (const auto & pt : ego_oriented_bound) {
points.push_back(lanelet::Point3d(pt));
}
return points;
};

const auto getMostInnerLane = [&](const lanelet::ConstLanelet & lane) -> lanelet::ConstLanelet {
const auto getMostInnerLane =
[&](const lanelet::ConstLanelet & lane) -> std::pair<lanelet::ConstLanelet, bool> {

Check warning on line 726 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

Codecov / codecov/patch

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp#L726

Added line #L726 was not covered by tests
const auto getInnerLane =
left_side_parking ? &RouteHandler::getMostRightLanelet : &RouteHandler::getMostLeftLanelet;
const auto getOppositeLane = left_side_parking ? &RouteHandler::getRightOppositeLanelets
: &RouteHandler::getLeftOppositeLanelets;
const auto inner_lane = (route_handler.*getInnerLane)(lane, true, true);
const auto opposite_lanes = (route_handler.*getOppositeLane)(inner_lane);
return opposite_lanes.empty() ? inner_lane : opposite_lanes.front();
return std::make_pair(
opposite_lanes.empty() ? inner_lane : opposite_lanes.front(), !opposite_lanes.empty());
};

lanelet::Points3d outer_bound_points{};
lanelet::Points3d inner_bound_points{};
for (const auto & lane : pull_over_lanes) {
const auto current_outer_bound_points = getBoundPoints(lane, true);
const auto most_inner_lane = getMostInnerLane(lane);
const auto current_inner_bound_points = getBoundPoints(most_inner_lane, false);
const auto current_outer_bound_points = getBoundPoints(lane, true, false);
const auto most_inner_lane_info = getMostInnerLane(lane);
const auto current_inner_bound_points =
getBoundPoints(most_inner_lane_info.first, false, most_inner_lane_info.second);

Check warning on line 743 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

createDepartureCheckLanelet increases in cyclomatic complexity from 11 to 12, 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.
outer_bound_points = combineLanePoints(outer_bound_points, current_outer_bound_points);
inner_bound_points = combineLanePoints(inner_bound_points, current_inner_bound_points);
}
Expand Down
Loading