-
Notifications
You must be signed in to change notification settings - Fork 755
feat(goal_planner): check pull over lane crossing validity when triggering candidate generation thread #10784
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
base: main
Are you sure you want to change the base?
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,4 +1,4 @@ | ||
// Copyright 2021 Tier IV, Inc. | ||
Check notice on line 1 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp
|
||
// | ||
// Licensed under the Apache License, Version 2.0 (the "License"); | ||
// you may not use this file except in compliance with the License. | ||
|
@@ -1076,4 +1076,51 @@ | |
path.points.size(); | ||
} | ||
|
||
std::optional<lanelet::ConstLanelet> find_lane_change_completed_lanelet( | ||
Check warning on line 1079 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp
|
||
const PathWithLaneId & path, const lanelet::LaneletMapConstPtr lanelet_map, | ||
const lanelet::routing::RoutingGraphConstPtr routing_graph) | ||
{ | ||
std::vector<lanelet::Id> path_lane_ids; | ||
for (const auto & point : path.points) { | ||
const auto & lane_ids = point.lane_ids; | ||
for (const auto & lane_id : lane_ids) { | ||
if (std::find(path_lane_ids.begin(), path_lane_ids.end(), lane_id) == path_lane_ids.end()) { | ||
path_lane_ids.push_back(lane_id); | ||
} | ||
} | ||
} | ||
|
||
if (path_lane_ids.size() < 2) { | ||
return std::nullopt; | ||
Check warning on line 1094 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp
|
||
} | ||
for (unsigned i = 0, j = 1; i < path_lane_ids.size() && j < path_lane_ids.size(); i++, j++) { | ||
const auto & lane1 = lanelet_map->laneletLayer.get(path_lane_ids.at(i)); | ||
const auto & lane2 = lanelet_map->laneletLayer.get(path_lane_ids.at(j)); | ||
const auto & followings = routing_graph->following(lane1); | ||
if (std::any_of(followings.begin(), followings.end(), [&](const auto & lane) { | ||
return lane.id() == lane2.id(); | ||
})) { | ||
continue; | ||
} | ||
return lane2; | ||
} | ||
return std::nullopt; | ||
Check warning on line 1107 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp
|
||
} | ||
Check warning on line 1108 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp
|
||
|
||
lanelet::ConstLanelets get_reference_lanelets_for_pullover( | ||
Check warning on line 1110 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp
|
||
const PathWithLaneId & path, const std::shared_ptr<const PlannerData> & planner_data, | ||
const double backward_length, const double forward_length) | ||
{ | ||
const auto & routing_graph = planner_data->route_handler->getRoutingGraphPtr(); | ||
Check warning on line 1114 in planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/util.cpp
|
||
const auto & lanelet_map = planner_data->route_handler->getLaneletMapPtr(); | ||
const auto lane_change_complete_lane = | ||
find_lane_change_completed_lanelet(path, lanelet_map, routing_graph); | ||
if (!lane_change_complete_lane) { | ||
return utils::getExtendedCurrentLanesFromPath( | ||
path, planner_data, backward_length, forward_length, | ||
/*forward_only_in_route*/ false); | ||
} | ||
return planner_data->route_handler->getLaneletSequence( | ||
*lane_change_complete_lane, backward_length, forward_length); | ||
Comment on lines
+1123
to
+1124
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. this can't get lanes after goal? |
||
} | ||
} // namespace autoware::behavior_path_planner::goal_planner_utils |
Uh oh!
There was an error while loading. Please reload this page.