Skip to content

Commit d584f3d

Browse files
feat(behavior_path_planner_common): add safety target object located on shoulder lane (autowarefoundation#6839)
feat(behavior_path_planner_common): add target object located on shoulder lane Signed-off-by: kyoichi-sugahara <kyoichi.sugahara@tier4.jp>
1 parent 232d882 commit d584f3d

File tree

1 file changed

+17
-3
lines changed

1 file changed

+17
-3
lines changed

planning/behavior_path_planner_common/src/utils/path_safety_checker/objects_filtering.cpp

+17-3
Original file line numberDiff line numberDiff line change
@@ -330,8 +330,9 @@ TargetObjectsOnLane createTargetObjectsOnLane(
330330

331331
lanelet::ConstLanelets all_left_lanelets;
332332
lanelet::ConstLanelets all_right_lanelets;
333+
// TODO(sugahara): consider right side parking and define right shoulder lanelets
334+
lanelet::ConstLanelets all_left_shoulder_lanelets;
333335

334-
// Define lambda functions to update left and right lanelets
335336
const auto update_left_lanelets = [&](const lanelet::ConstLanelet & target_lane) {
336337
const auto left_lanelets = route_handler->getAllLeftSharedLinestringLanelets(
337338
target_lane, include_opposite, invert_opposite);
@@ -345,13 +346,23 @@ TargetObjectsOnLane createTargetObjectsOnLane(
345346
all_right_lanelets.end(), right_lanelets.begin(), right_lanelets.end());
346347
};
347348

348-
// Update left and right lanelets for each current lane
349+
const auto update_left_shoulder_lanelet = [&](const lanelet::ConstLanelet & target_lane) {
350+
lanelet::ConstLanelet neighbor_shoulder_lane{};
351+
const bool shoulder_lane_is_found =
352+
route_handler->getLeftShoulderLanelet(target_lane, &neighbor_shoulder_lane);
353+
if (shoulder_lane_is_found) {
354+
all_left_shoulder_lanelets.insert(all_left_shoulder_lanelets.end(), neighbor_shoulder_lane);
355+
}
356+
};
357+
349358
for (const auto & current_lane : current_lanes) {
350359
update_left_lanelets(current_lane);
351360
update_right_lanelets(current_lane);
361+
update_left_shoulder_lanelet(current_lane);
352362
}
353363

354364
TargetObjectsOnLane target_objects_on_lane{};
365+
355366
const auto append_objects_on_lane = [&](auto & lane_objects, const auto & check_lanes) {
356367
std::for_each(
357368
filtered_objects.objects.begin(), filtered_objects.objects.end(), [&](const auto & object) {
@@ -362,7 +373,7 @@ TargetObjectsOnLane createTargetObjectsOnLane(
362373
});
363374
};
364375

365-
// TODO(Sugahara): Consider shoulder and other lane objects
376+
// TODO(Sugahara): Consider other lane objects
366377
if (object_lane_configuration.check_current_lane && !current_lanes.empty()) {
367378
append_objects_on_lane(target_objects_on_lane.on_current_lane, current_lanes);
368379
}
@@ -372,6 +383,9 @@ TargetObjectsOnLane createTargetObjectsOnLane(
372383
if (object_lane_configuration.check_right_lane && !all_right_lanelets.empty()) {
373384
append_objects_on_lane(target_objects_on_lane.on_right_lane, all_right_lanelets);
374385
}
386+
if (object_lane_configuration.check_shoulder_lane && !all_left_shoulder_lanelets.empty()) {
387+
append_objects_on_lane(target_objects_on_lane.on_shoulder_lane, all_left_shoulder_lanelets);
388+
}
375389

376390
return target_objects_on_lane;
377391
}

0 commit comments

Comments
 (0)