Skip to content

Commit 7b9cb82

Browse files
committed
fix(avoidance): bug in the logic to judge whether it's a parked vehicle (autowarefoundation#6768)
fix(avoidance): adjacent lane check for ambiguous stopped vehicle Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
1 parent ae4176c commit 7b9cb82

File tree

3 files changed

+5
-45
lines changed

3 files changed

+5
-45
lines changed

planning/behavior_path_avoidance_module/include/behavior_path_avoidance_module/utils.hpp

-4
Original file line numberDiff line numberDiff line change
@@ -85,10 +85,6 @@ lanelet::ConstLanelets getAdjacentLane(
8585
const std::shared_ptr<const PlannerData> & planner_data,
8686
const std::shared_ptr<AvoidanceParameters> & parameters, const bool is_right_shift);
8787

88-
lanelet::ConstLanelets getTargetLanelets(
89-
const std::shared_ptr<const PlannerData> & planner_data, lanelet::ConstLanelets & route_lanelets,
90-
const double left_offset, const double right_offset);
91-
9288
lanelet::ConstLanelets getCurrentLanesFromPath(
9389
const PathWithLaneId & path, const std::shared_ptr<const PlannerData> & planner_data);
9490

planning/behavior_path_avoidance_module/src/scene.cpp

-1
Original file line numberDiff line numberDiff line change
@@ -318,7 +318,6 @@ void AvoidanceModule::fillAvoidanceTargetObjects(
318318
using utils::avoidance::fillAvoidanceNecessity;
319319
using utils::avoidance::fillObjectStoppableJudge;
320320
using utils::avoidance::filterTargetObjects;
321-
using utils::avoidance::getTargetLanelets;
322321
using utils::avoidance::separateObjectsByPath;
323322
using utils::avoidance::updateRoadShoulderDistance;
324323

planning/behavior_path_avoidance_module/src/utils.cpp

+5-40
Original file line numberDiff line numberDiff line change
@@ -668,9 +668,11 @@ bool isNeverAvoidanceTarget(
668668
}
669669

670670
if (object.is_on_ego_lane) {
671-
if (
672-
planner_data->route_handler->getRightLanelet(object.overhang_lanelet).has_value() &&
673-
planner_data->route_handler->getLeftLanelet(object.overhang_lanelet).has_value()) {
671+
const auto right_lane =
672+
planner_data->route_handler->getRightLanelet(object.overhang_lanelet, true, false);
673+
const auto left_lane =
674+
planner_data->route_handler->getLeftLanelet(object.overhang_lanelet, true, false);
675+
if (right_lane.has_value() && left_lane.has_value()) {
674676
object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT;
675677
RCLCPP_DEBUG(rclcpp::get_logger(__func__), "object isn't on the edge lane. never avoid it.");
676678
return true;
@@ -1312,43 +1314,6 @@ std::vector<DrivableAreaInfo::Obstacle> generateObstaclePolygonsForDrivableArea(
13121314
return obstacles_for_drivable_area;
13131315
}
13141316

1315-
lanelet::ConstLanelets getTargetLanelets(
1316-
const std::shared_ptr<const PlannerData> & planner_data, lanelet::ConstLanelets & route_lanelets,
1317-
const double left_offset, const double right_offset)
1318-
{
1319-
const auto & rh = planner_data->route_handler;
1320-
1321-
lanelet::ConstLanelets target_lanelets{};
1322-
for (const auto & lane : route_lanelets) {
1323-
auto l_offset = 0.0;
1324-
auto r_offset = 0.0;
1325-
1326-
const auto opt_left_lane = rh->getLeftLanelet(lane);
1327-
if (opt_left_lane) {
1328-
target_lanelets.push_back(opt_left_lane.value());
1329-
} else {
1330-
l_offset = left_offset;
1331-
}
1332-
1333-
const auto opt_right_lane = rh->getRightLanelet(lane);
1334-
if (opt_right_lane) {
1335-
target_lanelets.push_back(opt_right_lane.value());
1336-
} else {
1337-
r_offset = right_offset;
1338-
}
1339-
1340-
const auto right_opposite_lanes = rh->getRightOppositeLanelets(lane);
1341-
if (!right_opposite_lanes.empty()) {
1342-
target_lanelets.push_back(right_opposite_lanes.front());
1343-
}
1344-
1345-
const auto expand_lane = lanelet::utils::getExpandedLanelet(lane, l_offset, r_offset);
1346-
target_lanelets.push_back(expand_lane);
1347-
}
1348-
1349-
return target_lanelets;
1350-
}
1351-
13521317
lanelet::ConstLanelets getCurrentLanesFromPath(
13531318
const PathWithLaneId & path, const std::shared_ptr<const PlannerData> & planner_data)
13541319
{

0 commit comments

Comments
 (0)