Skip to content

Commit

Permalink
fix(goal_planner): fix multiple lane ids of shift pull over
Browse files Browse the repository at this point in the history
Signed-off-by: kosuke55 <[email protected]>

fix vel
  • Loading branch information
kosuke55 committed Nov 18, 2024
1 parent 4a4db99 commit 4d4d6e3
Showing 1 changed file with 17 additions and 19 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -221,14 +221,23 @@ std::optional<PullOverPath> ShiftPullOver::generatePullOverPath(
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);
}
Expand All @@ -237,24 +246,13 @@ std::optional<PullOverPath> ShiftPullOver::generatePullOverPath(
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

0 comments on commit 4d4d6e3

Please sign in to comment.