Skip to content

Commit f5b95df

Browse files
maxime-clemshmpwk
authored andcommitted
feat(out_of_lane): add option to ignore overlaps in lane changes (autowarefoundation#6991)
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
1 parent e521734 commit f5b95df

File tree

4 files changed

+16
-0
lines changed

4 files changed

+16
-0
lines changed

planning/behavior_velocity_out_of_lane_module/config/out_of_lane.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@
33
out_of_lane: # module to stop or slowdown before overlapping another lane with other objects
44
mode: ttc # mode used to consider a conflict with an object. "threshold", "intervals", or "ttc"
55
skip_if_already_overlapping: true # do not run this module when ego already overlaps another lane
6+
ignore_overlaps_over_lane_changeable_lanelets: true # if true, overlaps on lane changeable lanelets are ignored
67

78
threshold:
89
time_threshold: 5.0 # [s] consider objects that will reach an overlap within this time

planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.cpp

+11
Original file line numberDiff line numberDiff line change
@@ -78,6 +78,15 @@ lanelet::ConstLanelets calculate_path_lanelets(
7878
return path_lanelets;
7979
}
8080

81+
void add_lane_changeable_lanelets(
82+
lanelet::ConstLanelets & lanelets_to_ignore, const lanelet::ConstLanelets & path_lanelets,
83+
const route_handler::RouteHandler & route_handler)
84+
{
85+
for (const auto & path_lanelet : path_lanelets)
86+
for (const auto & ll : route_handler.getLaneChangeableNeighbors(path_lanelet))
87+
if (!contains_lanelet(lanelets_to_ignore, ll.id())) lanelets_to_ignore.push_back(ll);
88+
}
89+
8190
lanelet::ConstLanelets calculate_ignored_lanelets(
8291
const EgoData & ego_data, const lanelet::ConstLanelets & path_lanelets,
8392
const route_handler::RouteHandler & route_handler, const PlannerParam & params)
@@ -93,6 +102,8 @@ lanelet::ConstLanelets calculate_ignored_lanelets(
93102
const auto is_path_lanelet = contains_lanelet(path_lanelets, l.second.id());
94103
if (!is_path_lanelet) ignored_lanelets.push_back(l.second);
95104
}
105+
if (params.ignore_overlaps_over_lane_changeable_lanelets)
106+
add_lane_changeable_lanelets(ignored_lanelets, path_lanelets, route_handler);
96107
return ignored_lanelets;
97108
}
98109

planning/behavior_velocity_out_of_lane_module/src/manager.cpp

+2
Original file line numberDiff line numberDiff line change
@@ -38,6 +38,8 @@ OutOfLaneModuleManager::OutOfLaneModuleManager(rclcpp::Node & node)
3838
pp.mode = getOrDeclareParameter<std::string>(node, ns + ".mode");
3939
pp.skip_if_already_overlapping =
4040
getOrDeclareParameter<bool>(node, ns + ".skip_if_already_overlapping");
41+
pp.ignore_overlaps_over_lane_changeable_lanelets =
42+
getOrDeclareParameter<bool>(node, ns + ".ignore_overlaps_over_lane_changeable_lanelets");
4143

4244
pp.time_threshold = getOrDeclareParameter<double>(node, ns + ".threshold.time_threshold");
4345
pp.intervals_ego_buffer = getOrDeclareParameter<double>(node, ns + ".intervals.ego_time_buffer");

planning/behavior_velocity_out_of_lane_module/src/types.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,8 @@ struct PlannerParam
3939
std::string mode; // mode used to consider a conflict with an object
4040
bool skip_if_already_overlapping; // if true, do not run the module when ego already overlaps
4141
// another lane
42+
bool ignore_overlaps_over_lane_changeable_lanelets; // if true, overlaps on lane changeable
43+
// lanelets are ignored
4244

4345
double time_threshold; // [s](mode="threshold") objects time threshold
4446
double intervals_ego_buffer; // [s](mode="intervals") buffer to extend the ego time range

0 commit comments

Comments
 (0)