Skip to content

Commit 74f0bbe

Browse files
committed
fix(avoidance): safety check target lanes (autowarefoundation#6324)
* fix(avoidance): improve safety check lanes Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> * fix(avoidance): check both side lane if need Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com> --------- Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent 9425a12 commit 74f0bbe

File tree

3 files changed

+56
-23
lines changed

3 files changed

+56
-23
lines changed

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -78,6 +78,7 @@ std::vector<DrivableAreaInfo::Obstacle> generateObstaclePolygonsForDrivableArea(
7878
const double vehicle_width);
7979

8080
lanelet::ConstLanelets getAdjacentLane(
81+
const lanelet::ConstLanelet & current_lane,
8182
const std::shared_ptr<const PlannerData> & planner_data,
8283
const std::shared_ptr<AvoidanceParameters> & parameters, const bool is_right_shift);
8384

@@ -147,8 +148,8 @@ AvoidLineArray combineRawShiftLinesWithUniqueCheck(
147148

148149
std::vector<ExtendedPredictedObject> getSafetyCheckTargetObjects(
149150
const AvoidancePlanningData & data, const std::shared_ptr<const PlannerData> & planner_data,
150-
const std::shared_ptr<AvoidanceParameters> & parameters, const bool is_right_shift,
151-
DebugData & debug);
151+
const std::shared_ptr<AvoidanceParameters> & parameters, const bool has_left_shift,
152+
const bool has_right_shift, DebugData & debug);
152153

153154
std::pair<PredictedObjects, PredictedObjects> separateObjectsByPath(
154155
const PathWithLaneId & reference_path, const PathWithLaneId & spline_path,

planning/behavior_path_avoidance_module/src/scene.cpp

+14-5
Original file line numberDiff line numberDiff line change
@@ -695,30 +695,39 @@ bool AvoidanceModule::isSafePath(
695695
}
696696

697697
const auto ego_idx = planner_data_->findEgoIndex(shifted_path.path.points);
698-
const auto is_right_shift = [&]() -> std::optional<bool> {
698+
699+
const auto has_left_shift = [&]() {
699700
for (size_t i = ego_idx; i < shifted_path.shift_length.size(); i++) {
700701
const auto length = shifted_path.shift_length.at(i);
701702

702703
if (parameters_->lateral_avoid_check_threshold < length) {
703-
return false;
704+
return true;
704705
}
706+
}
707+
708+
return false;
709+
}();
710+
711+
const auto has_right_shift = [&]() {
712+
for (size_t i = ego_idx; i < shifted_path.shift_length.size(); i++) {
713+
const auto length = shifted_path.shift_length.at(i);
705714

706715
if (parameters_->lateral_avoid_check_threshold < -1.0 * length) {
707716
return true;
708717
}
709718
}
710719

711-
return std::nullopt;
720+
return false;
712721
}();
713722

714-
if (!is_right_shift.has_value()) {
723+
if (!has_left_shift && !has_right_shift) {
715724
return true;
716725
}
717726

718727
const auto hysteresis_factor = safe_ ? 1.0 : parameters_->hysteresis_factor_expand_rate;
719728

720729
const auto safety_check_target_objects = utils::avoidance::getSafetyCheckTargetObjects(
721-
avoid_data_, planner_data_, parameters_, is_right_shift.value(), debug);
730+
avoid_data_, planner_data_, parameters_, has_left_shift, has_right_shift, debug);
722731

723732
if (safety_check_target_objects.empty()) {
724733
return true;

planning/behavior_path_avoidance_module/src/utils.cpp

+39-16
Original file line numberDiff line numberDiff line change
@@ -1263,11 +1263,13 @@ lanelet::ConstLanelets getCurrentLanesFromPath(
12631263
throw std::logic_error("empty path.");
12641264
}
12651265

1266-
if (path.points.front().lane_ids.empty()) {
1266+
const auto idx = planner_data->findEgoIndex(path.points);
1267+
1268+
if (path.points.at(idx).lane_ids.empty()) {
12671269
throw std::logic_error("empty lane ids.");
12681270
}
12691271

1270-
const auto start_id = path.points.front().lane_ids.front();
1272+
const auto start_id = path.points.at(idx).lane_ids.front();
12711273
const auto start_lane = planner_data->route_handler->getLaneletsFromId(start_id);
12721274
const auto & p = planner_data->parameters;
12731275

@@ -1814,6 +1816,7 @@ AvoidLineArray combineRawShiftLinesWithUniqueCheck(
18141816
}
18151817

18161818
lanelet::ConstLanelets getAdjacentLane(
1819+
const lanelet::ConstLanelet & current_lane,
18171820
const std::shared_ptr<const PlannerData> & planner_data,
18181821
const std::shared_ptr<AvoidanceParameters> & parameters, const bool is_right_shift)
18191822
{
@@ -1822,18 +1825,17 @@ lanelet::ConstLanelets getAdjacentLane(
18221825
const auto & backward_distance = parameters->safety_check_backward_distance;
18231826
const auto & vehicle_pose = planner_data->self_odometry->pose.pose;
18241827

1825-
lanelet::ConstLanelet current_lane;
1826-
if (!rh->getClosestLaneletWithinRoute(vehicle_pose, &current_lane)) {
1827-
RCLCPP_ERROR(
1828-
rclcpp::get_logger("behavior_path_planner").get_child("avoidance"),
1829-
"failed to find closest lanelet within route!!!");
1830-
return {}; // TODO(Satoshi Ota)
1831-
}
1832-
18331828
const auto ego_succeeding_lanes =
18341829
rh->getLaneletSequence(current_lane, vehicle_pose, backward_distance, forward_distance);
18351830

18361831
lanelet::ConstLanelets lanes{};
1832+
1833+
const auto exist = [&lanes](const auto id) {
1834+
const auto itr = std::find_if(
1835+
lanes.begin(), lanes.end(), [&id](const auto & lane) { return lane.id() == id; });
1836+
return itr != lanes.end();
1837+
};
1838+
18371839
for (const auto & lane : ego_succeeding_lanes) {
18381840
const auto opt_left_lane = rh->getLeftLanelet(lane, true, false);
18391841
if (!is_right_shift && opt_left_lane) {
@@ -1848,6 +1850,20 @@ lanelet::ConstLanelets getAdjacentLane(
18481850
const auto right_opposite_lanes = rh->getRightOppositeLanelets(lane);
18491851
if (is_right_shift && !right_opposite_lanes.empty()) {
18501852
lanes.push_back(right_opposite_lanes.front());
1853+
1854+
for (const auto & prev_lane : rh->getPreviousLanelets(right_opposite_lanes.front())) {
1855+
if (!exist(prev_lane.id())) {
1856+
lanes.push_back(prev_lane);
1857+
}
1858+
}
1859+
}
1860+
}
1861+
1862+
for (const auto & lane : lanes) {
1863+
for (const auto & next_lane : rh->getNextLanelets(lane)) {
1864+
if (!exist(next_lane.id())) {
1865+
lanes.push_back(next_lane);
1866+
}
18511867
}
18521868
}
18531869

@@ -1856,14 +1872,14 @@ lanelet::ConstLanelets getAdjacentLane(
18561872

18571873
std::vector<ExtendedPredictedObject> getSafetyCheckTargetObjects(
18581874
const AvoidancePlanningData & data, const std::shared_ptr<const PlannerData> & planner_data,
1859-
const std::shared_ptr<AvoidanceParameters> & parameters, const bool is_right_shift,
1860-
DebugData & debug)
1875+
const std::shared_ptr<AvoidanceParameters> & parameters, const bool has_left_shift,
1876+
const bool has_right_shift, DebugData & debug)
18611877
{
18621878
const auto & p = parameters;
18631879
const auto check_right_lanes =
1864-
(is_right_shift && p->check_shift_side_lane) || (!is_right_shift && p->check_other_side_lane);
1880+
(has_right_shift && p->check_shift_side_lane) || (has_left_shift && p->check_other_side_lane);
18651881
const auto check_left_lanes =
1866-
(!is_right_shift && p->check_shift_side_lane) || (is_right_shift && p->check_other_side_lane);
1882+
(has_left_shift && p->check_shift_side_lane) || (has_right_shift && p->check_other_side_lane);
18671883

18681884
std::vector<ExtendedPredictedObject> target_objects;
18691885

@@ -1901,9 +1917,16 @@ std::vector<ExtendedPredictedObject> getSafetyCheckTargetObjects(
19011917
return ret;
19021918
}();
19031919

1920+
lanelet::ConstLanelet closest_lanelet;
1921+
const auto & ego_pose = planner_data->self_odometry->pose.pose;
1922+
if (!lanelet::utils::query::getClosestLanelet(
1923+
data.current_lanelets, ego_pose, &closest_lanelet)) {
1924+
return {};
1925+
}
1926+
19041927
// check right lanes
19051928
if (check_right_lanes) {
1906-
const auto check_lanes = getAdjacentLane(planner_data, p, true);
1929+
const auto check_lanes = getAdjacentLane(closest_lanelet, planner_data, p, true);
19071930

19081931
if (p->check_other_object) {
19091932
const auto [targets, others] = utils::path_safety_checker::separateObjectsByLanelets(
@@ -1925,7 +1948,7 @@ std::vector<ExtendedPredictedObject> getSafetyCheckTargetObjects(
19251948

19261949
// check left lanes
19271950
if (check_left_lanes) {
1928-
const auto check_lanes = getAdjacentLane(planner_data, p, false);
1951+
const auto check_lanes = getAdjacentLane(closest_lanelet, planner_data, p, false);
19291952

19301953
if (p->check_other_object) {
19311954
const auto [targets, others] = utils::path_safety_checker::separateObjectsByLanelets(

0 commit comments

Comments
 (0)