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(goal_planner): fix multiple lane ids of shift pull over #9360

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
Original file line number Diff line number Diff line change
Expand Up @@ -221,40 +221,38 @@
shifted_path.path.points.push_back(p);
}

// combine road lanes and shoulder lanes to find closest lanelet id
const auto lanes = std::invoke([&]() -> lanelet::ConstLanelets {
auto lanes = road_lanes;
lanes.insert(lanes.end(), shoulder_lanes.begin(), shoulder_lanes.end());
return std::move(lanes);
});

// set goal pose with velocity 0
{
PathPointWithLaneId p{};
p.point.longitudinal_velocity_mps = 0.0;
p.point.pose = goal_pose;
p.lane_ids = shifted_path.path.points.back().lane_ids;
for (const auto & lane : shoulder_lanes) {
p.lane_ids.push_back(lane.id());
lanelet::Lanelet goal_lanelet{};
if (lanelet::utils::query::getClosestLanelet(lanes, goal_pose, &goal_lanelet)) {
p.lane_ids = {goal_lanelet.id()};
} else {
p.lane_ids = shifted_path.path.points.back().lane_ids;
}
shifted_path.path.points.push_back(p);
}

// set lane_id and velocity to shifted_path
for (size_t i = path_shifter.getShiftLines().front().start_idx;
i < shifted_path.path.points.size() - 1; ++i) {
auto & point = shifted_path.path.points.at(i);
// set velocity
point.point.longitudinal_velocity_mps =
std::min(point.point.longitudinal_velocity_mps, static_cast<float>(pull_over_velocity));

// add target lanes to points after shift start
// add road lane_ids if not found
for (const auto id : shifted_path.path.points.back().lane_ids) {
if (std::find(point.lane_ids.begin(), point.lane_ids.end(), id) == point.lane_ids.end()) {
point.lane_ids.push_back(id);
}
}
// add shoulder lane_id if not found
for (const auto & lane : shoulder_lanes) {
if (
std::find(point.lane_ids.begin(), point.lane_ids.end(), lane.id()) ==
point.lane_ids.end()) {
point.lane_ids.push_back(lane.id());
}
lanelet::Lanelet lanelet{};
if (lanelet::utils::query::getClosestLanelet(lanes, point.point.pose, &lanelet)) {
point.lane_ids = {lanelet.id()}; // overwrite lane_ids
} else {
point.lane_ids = shifted_path.path.points.at(i - 1).lane_ids;

Check notice on line 255 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ Getting better: Complex Method

ShiftPullOver::generatePullOverPath decreases in cyclomatic complexity from 15 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.

Check notice on line 255 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/pull_over_planner/shift_pull_over.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Bumpy Road Ahead

ShiftPullOver::generatePullOverPath is no longer above the threshold for logical blocks with deeply nested code
}
}

Expand Down
Loading