Skip to content

Commit e7f0939

Browse files
maxime-clemTomohitoAndo
authored andcommitted
fix(out_of_lane): calculate path lanelets that we can miss during a lane change (autowarefoundation#6600)
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
1 parent 747d701 commit e7f0939

File tree

2 files changed

+46
-2
lines changed

2 files changed

+46
-2
lines changed

planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.cpp

+39-2
Original file line numberDiff line numberDiff line change
@@ -23,12 +23,47 @@
2323

2424
namespace behavior_velocity_planner::out_of_lane
2525
{
26+
27+
lanelet::ConstLanelets consecutive_lanelets(
28+
const route_handler::RouteHandler & route_handler, const lanelet::ConstLanelet & lanelet)
29+
{
30+
lanelet::ConstLanelets consecutives = route_handler.getRoutingGraphPtr()->following(lanelet);
31+
const auto previous = route_handler.getRoutingGraphPtr()->previous(lanelet);
32+
consecutives.insert(consecutives.end(), previous.begin(), previous.end());
33+
return consecutives;
34+
}
35+
36+
lanelet::ConstLanelets get_missing_lane_change_lanelets(
37+
lanelet::ConstLanelets & path_lanelets, const route_handler::RouteHandler & route_handler)
38+
{
39+
lanelet::ConstLanelets missing_lane_change_lanelets;
40+
const auto & routing_graph = *route_handler.getRoutingGraphPtr();
41+
lanelet::ConstLanelets adjacents;
42+
lanelet::ConstLanelets consecutives;
43+
for (const auto & ll : path_lanelets) {
44+
const auto consecutives_of_ll = consecutive_lanelets(route_handler, ll);
45+
std::copy_if(
46+
consecutives_of_ll.begin(), consecutives_of_ll.end(), std::back_inserter(consecutives),
47+
[&](const auto & l) { return !contains_lanelet(consecutives, l.id()); });
48+
const auto adjacents_of_ll = routing_graph.besides(ll);
49+
std::copy_if(
50+
adjacents_of_ll.begin(), adjacents_of_ll.end(), std::back_inserter(adjacents),
51+
[&](const auto & l) { return !contains_lanelet(adjacents, l.id()); });
52+
}
53+
std::copy_if(
54+
adjacents.begin(), adjacents.end(), std::back_inserter(missing_lane_change_lanelets),
55+
[&](const auto & l) {
56+
return !contains_lanelet(missing_lane_change_lanelets, l.id()) &&
57+
!contains_lanelet(path_lanelets, l.id()) && contains_lanelet(consecutives, l.id());
58+
});
59+
return missing_lane_change_lanelets;
60+
}
61+
2662
lanelet::ConstLanelets calculate_path_lanelets(
2763
const EgoData & ego_data, const route_handler::RouteHandler & route_handler)
2864
{
2965
const auto lanelet_map_ptr = route_handler.getLaneletMapPtr();
30-
lanelet::ConstLanelets path_lanelets =
31-
planning_utils::getLaneletsOnPath(ego_data.path, lanelet_map_ptr, ego_data.pose);
66+
lanelet::ConstLanelets path_lanelets;
3267
lanelet::BasicLineString2d path_ls;
3368
for (const auto & p : ego_data.path.points)
3469
path_ls.emplace_back(p.point.pose.position.x, p.point.pose.position.y);
@@ -37,6 +72,8 @@ lanelet::ConstLanelets calculate_path_lanelets(
3772
if (!contains_lanelet(path_lanelets, dist_lanelet.second.id()))
3873
path_lanelets.push_back(dist_lanelet.second);
3974
}
75+
const auto missing_lanelets = get_missing_lane_change_lanelets(path_lanelets, route_handler);
76+
path_lanelets.insert(path_lanelets.end(), missing_lanelets.begin(), missing_lanelets.end());
4077
return path_lanelets;
4178
}
4279

planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.hpp

+7
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,13 @@ inline bool contains_lanelet(const lanelet::ConstLanelets & lanelets, const lane
4141
/// @return lanelets crossed by the ego vehicle
4242
lanelet::ConstLanelets calculate_path_lanelets(
4343
const EgoData & ego_data, const route_handler::RouteHandler & route_handler);
44+
/// @brief calculate lanelets that may not be crossed by the path but may be overlapped during a
45+
/// lane change
46+
/// @param [in] path_lanelets lanelets driven by the ego vehicle
47+
/// @param [in] route_handler route handler
48+
/// @return lanelets that may be overlapped by a lane change (and are not already in path_lanelets)
49+
lanelet::ConstLanelets get_missing_lane_change_lanelets(
50+
lanelet::ConstLanelets & path_lanelets, const route_handler::RouteHandler & route_handler);
4451
/// @brief calculate lanelets that should be ignored
4552
/// @param [in] ego_data data about the ego vehicle
4653
/// @param [in] path_lanelets lanelets driven by the ego vehicle

0 commit comments

Comments
 (0)