@@ -2318,14 +2318,16 @@ DrivableLanes generateExpandedDrivableLanes(
2318
2318
current_drivable_lanes.left_lane = lanelet;
2319
2319
current_drivable_lanes.right_lane = lanelet;
2320
2320
2321
- if (! parameters->use_adjacent_lane ) {
2321
+ if (parameters->use_lane_type == " current_lane " ) {
2322
2322
return current_drivable_lanes;
2323
2323
}
2324
2324
2325
+ const auto use_opposite_lane = parameters->use_lane_type == " opposite_direction_lane" ;
2326
+
2325
2327
// 1. get left/right side lanes
2326
2328
const auto update_left_lanelets = [&](const lanelet::ConstLanelet & target_lane) {
2327
- const auto all_left_lanelets = route_handler-> getAllLeftSharedLinestringLanelets (
2328
- target_lane, parameters-> use_opposite_lane , true );
2329
+ const auto all_left_lanelets =
2330
+ route_handler-> getAllLeftSharedLinestringLanelets ( target_lane, use_opposite_lane, true );
2329
2331
if (!all_left_lanelets.empty ()) {
2330
2332
current_drivable_lanes.left_lane = all_left_lanelets.back (); // leftmost lanelet
2331
2333
pushUniqueVector (
@@ -2334,8 +2336,8 @@ DrivableLanes generateExpandedDrivableLanes(
2334
2336
}
2335
2337
};
2336
2338
const auto update_right_lanelets = [&](const lanelet::ConstLanelet & target_lane) {
2337
- const auto all_right_lanelets = route_handler-> getAllRightSharedLinestringLanelets (
2338
- target_lane, parameters-> use_opposite_lane , true );
2339
+ const auto all_right_lanelets =
2340
+ route_handler-> getAllRightSharedLinestringLanelets ( target_lane, use_opposite_lane, true );
2339
2341
if (!all_right_lanelets.empty ()) {
2340
2342
current_drivable_lanes.right_lane = all_right_lanelets.back (); // rightmost lanelet
2341
2343
pushUniqueVector (
0 commit comments