Skip to content

Commit 94948a0

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 5fbf715 commit 94948a0

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
@@ -1259,11 +1259,13 @@ lanelet::ConstLanelets getCurrentLanesFromPath(
12591259
throw std::logic_error("empty path.");
12601260
}
12611261

1262-
if (path.points.front().lane_ids.empty()) {
1262+
const auto idx = planner_data->findEgoIndex(path.points);
1263+
1264+
if (path.points.at(idx).lane_ids.empty()) {
12631265
throw std::logic_error("empty lane ids.");
12641266
}
12651267

1266-
const auto start_id = path.points.front().lane_ids.front();
1268+
const auto start_id = path.points.at(idx).lane_ids.front();
12671269
const auto start_lane = planner_data->route_handler->getLaneletsFromId(start_id);
12681270
const auto & p = planner_data->parameters;
12691271

@@ -1810,6 +1812,7 @@ AvoidLineArray combineRawShiftLinesWithUniqueCheck(
18101812
}
18111813

18121814
lanelet::ConstLanelets getAdjacentLane(
1815+
const lanelet::ConstLanelet & current_lane,
18131816
const std::shared_ptr<const PlannerData> & planner_data,
18141817
const std::shared_ptr<AvoidanceParameters> & parameters, const bool is_right_shift)
18151818
{
@@ -1818,18 +1821,17 @@ lanelet::ConstLanelets getAdjacentLane(
18181821
const auto & backward_distance = parameters->safety_check_backward_distance;
18191822
const auto & vehicle_pose = planner_data->self_odometry->pose.pose;
18201823

1821-
lanelet::ConstLanelet current_lane;
1822-
if (!rh->getClosestLaneletWithinRoute(vehicle_pose, &current_lane)) {
1823-
RCLCPP_ERROR(
1824-
rclcpp::get_logger("behavior_path_planner").get_child("avoidance"),
1825-
"failed to find closest lanelet within route!!!");
1826-
return {}; // TODO(Satoshi Ota)
1827-
}
1828-
18291824
const auto ego_succeeding_lanes =
18301825
rh->getLaneletSequence(current_lane, vehicle_pose, backward_distance, forward_distance);
18311826

18321827
lanelet::ConstLanelets lanes{};
1828+
1829+
const auto exist = [&lanes](const auto id) {
1830+
const auto itr = std::find_if(
1831+
lanes.begin(), lanes.end(), [&id](const auto & lane) { return lane.id() == id; });
1832+
return itr != lanes.end();
1833+
};
1834+
18331835
for (const auto & lane : ego_succeeding_lanes) {
18341836
const auto opt_left_lane = rh->getLeftLanelet(lane, true, false);
18351837
if (!is_right_shift && opt_left_lane) {
@@ -1844,6 +1846,20 @@ lanelet::ConstLanelets getAdjacentLane(
18441846
const auto right_opposite_lanes = rh->getRightOppositeLanelets(lane);
18451847
if (is_right_shift && !right_opposite_lanes.empty()) {
18461848
lanes.push_back(right_opposite_lanes.front());
1849+
1850+
for (const auto & prev_lane : rh->getPreviousLanelets(right_opposite_lanes.front())) {
1851+
if (!exist(prev_lane.id())) {
1852+
lanes.push_back(prev_lane);
1853+
}
1854+
}
1855+
}
1856+
}
1857+
1858+
for (const auto & lane : lanes) {
1859+
for (const auto & next_lane : rh->getNextLanelets(lane)) {
1860+
if (!exist(next_lane.id())) {
1861+
lanes.push_back(next_lane);
1862+
}
18471863
}
18481864
}
18491865

@@ -1852,14 +1868,14 @@ lanelet::ConstLanelets getAdjacentLane(
18521868

18531869
std::vector<ExtendedPredictedObject> getSafetyCheckTargetObjects(
18541870
const AvoidancePlanningData & data, const std::shared_ptr<const PlannerData> & planner_data,
1855-
const std::shared_ptr<AvoidanceParameters> & parameters, const bool is_right_shift,
1856-
DebugData & debug)
1871+
const std::shared_ptr<AvoidanceParameters> & parameters, const bool has_left_shift,
1872+
const bool has_right_shift, DebugData & debug)
18571873
{
18581874
const auto & p = parameters;
18591875
const auto check_right_lanes =
1860-
(is_right_shift && p->check_shift_side_lane) || (!is_right_shift && p->check_other_side_lane);
1876+
(has_right_shift && p->check_shift_side_lane) || (has_left_shift && p->check_other_side_lane);
18611877
const auto check_left_lanes =
1862-
(!is_right_shift && p->check_shift_side_lane) || (is_right_shift && p->check_other_side_lane);
1878+
(has_left_shift && p->check_shift_side_lane) || (has_right_shift && p->check_other_side_lane);
18631879

18641880
std::vector<ExtendedPredictedObject> target_objects;
18651881

@@ -1897,9 +1913,16 @@ std::vector<ExtendedPredictedObject> getSafetyCheckTargetObjects(
18971913
return ret;
18981914
}();
18991915

1916+
lanelet::ConstLanelet closest_lanelet;
1917+
const auto & ego_pose = planner_data->self_odometry->pose.pose;
1918+
if (!lanelet::utils::query::getClosestLanelet(
1919+
data.current_lanelets, ego_pose, &closest_lanelet)) {
1920+
return {};
1921+
}
1922+
19001923
// check right lanes
19011924
if (check_right_lanes) {
1902-
const auto check_lanes = getAdjacentLane(planner_data, p, true);
1925+
const auto check_lanes = getAdjacentLane(closest_lanelet, planner_data, p, true);
19031926

19041927
if (p->check_other_object) {
19051928
const auto [targets, others] = utils::path_safety_checker::separateObjectsByLanelets(
@@ -1921,7 +1944,7 @@ std::vector<ExtendedPredictedObject> getSafetyCheckTargetObjects(
19211944

19221945
// check left lanes
19231946
if (check_left_lanes) {
1924-
const auto check_lanes = getAdjacentLane(planner_data, p, false);
1947+
const auto check_lanes = getAdjacentLane(closest_lanelet, planner_data, p, false);
19251948

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

0 commit comments

Comments
 (0)