@@ -575,9 +575,11 @@ bool isNeverAvoidanceTarget(
575
575
}
576
576
577
577
if (object.is_on_ego_lane ) {
578
- if (
579
- planner_data->route_handler ->getRightLanelet (object.overhang_lanelet ).has_value () &&
580
- planner_data->route_handler ->getLeftLanelet (object.overhang_lanelet ).has_value ()) {
578
+ const auto right_lane =
579
+ planner_data->route_handler ->getRightLanelet (object.overhang_lanelet , true , false );
580
+ const auto left_lane =
581
+ planner_data->route_handler ->getLeftLanelet (object.overhang_lanelet , true , false );
582
+ if (right_lane.has_value () && left_lane.has_value ()) {
581
583
object.reason = AvoidanceDebugFactor::NOT_PARKING_OBJECT;
582
584
RCLCPP_DEBUG (rclcpp::get_logger (__func__), " object isn't on the edge lane. never avoid it." );
583
585
return true ;
@@ -1219,43 +1221,6 @@ std::vector<DrivableAreaInfo::Obstacle> generateObstaclePolygonsForDrivableArea(
1219
1221
return obstacles_for_drivable_area;
1220
1222
}
1221
1223
1222
- lanelet::ConstLanelets getTargetLanelets (
1223
- const std::shared_ptr<const PlannerData> & planner_data, lanelet::ConstLanelets & route_lanelets,
1224
- const double left_offset, const double right_offset)
1225
- {
1226
- const auto & rh = planner_data->route_handler ;
1227
-
1228
- lanelet::ConstLanelets target_lanelets{};
1229
- for (const auto & lane : route_lanelets) {
1230
- auto l_offset = 0.0 ;
1231
- auto r_offset = 0.0 ;
1232
-
1233
- const auto opt_left_lane = rh->getLeftLanelet (lane);
1234
- if (opt_left_lane) {
1235
- target_lanelets.push_back (opt_left_lane.value ());
1236
- } else {
1237
- l_offset = left_offset;
1238
- }
1239
-
1240
- const auto opt_right_lane = rh->getRightLanelet (lane);
1241
- if (opt_right_lane) {
1242
- target_lanelets.push_back (opt_right_lane.value ());
1243
- } else {
1244
- r_offset = right_offset;
1245
- }
1246
-
1247
- const auto right_opposite_lanes = rh->getRightOppositeLanelets (lane);
1248
- if (!right_opposite_lanes.empty ()) {
1249
- target_lanelets.push_back (right_opposite_lanes.front ());
1250
- }
1251
-
1252
- const auto expand_lane = lanelet::utils::getExpandedLanelet (lane, l_offset, r_offset);
1253
- target_lanelets.push_back (expand_lane);
1254
- }
1255
-
1256
- return target_lanelets;
1257
- }
1258
-
1259
1224
lanelet::ConstLanelets getCurrentLanesFromPath (
1260
1225
const PathWithLaneId & path, const std::shared_ptr<const PlannerData> & planner_data)
1261
1226
{
0 commit comments