Skip to content

Commit 52c8df5

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

File tree

2 files changed

+30
-6
lines changed

2 files changed

+30
-6
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
}

planning/behavior_path_start_planner_module/src/start_planner_module.cpp

+13-3
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616

1717
#include "behavior_path_planner_common/utils/parking_departure/utils.hpp"
1818
#include "behavior_path_planner_common/utils/path_safety_checker/objects_filtering.hpp"
19+
#include "behavior_path_planner_common/utils/path_safety_checker/path_safety_checker_parameters.hpp"
1920
#include "behavior_path_planner_common/utils/path_utils.hpp"
2021
#include "behavior_path_start_planner_module/debug.hpp"
2122
#include "behavior_path_start_planner_module/util.hpp"
@@ -39,6 +40,7 @@
3940
#include <vector>
4041

4142
using behavior_path_planner::utils::parking_departure::initializeCollisionCheckDebugMap;
43+
using behavior_path_planner::utils::path_safety_checker::ExtendedPredictedObject;
4244
using motion_utils::calcLateralOffset;
4345
using motion_utils::calcLongitudinalOffsetPose;
4446
using tier4_autoware_utils::calcOffsetPose;
@@ -1324,10 +1326,18 @@ bool StartPlannerModule::isSafePath() const
13241326
debug_data_.target_objects_on_lane = target_objects_on_lane;
13251327
debug_data_.ego_predicted_path = ego_predicted_path;
13261328
}
1327-
1329+
std::vector<ExtendedPredictedObject> merged_target_object;
1330+
merged_target_object.reserve(
1331+
target_objects_on_lane.on_current_lane.size() + target_objects_on_lane.on_shoulder_lane.size());
1332+
merged_target_object.insert(
1333+
merged_target_object.end(), target_objects_on_lane.on_current_lane.begin(),
1334+
target_objects_on_lane.on_current_lane.end());
1335+
merged_target_object.insert(
1336+
merged_target_object.end(), target_objects_on_lane.on_shoulder_lane.begin(),
1337+
target_objects_on_lane.on_shoulder_lane.end());
13281338
return behavior_path_planner::utils::path_safety_checker::checkSafetyWithRSS(
1329-
pull_out_path, ego_predicted_path, target_objects_on_lane.on_current_lane,
1330-
debug_data_.collision_check, planner_data_->parameters, safety_check_params_->rss_params,
1339+
pull_out_path, ego_predicted_path, merged_target_object, debug_data_.collision_check,
1340+
planner_data_->parameters, safety_check_params_->rss_params,
13311341
objects_filtering_params_->use_all_predicted_path, hysteresis_factor);
13321342
}
13331343

0 commit comments

Comments
 (0)