Skip to content

Commit a11a3ee

Browse files
authored
chore(lane_change, QC): remove unused function (autowarefoundation#10188)
chore(lane_change): remove unused function Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent ca53a80 commit a11a3ee

File tree

2 files changed

+0
-123
lines changed
  • planning/behavior_path_planner/autoware_behavior_path_lane_change_module

2 files changed

+0
-123
lines changed

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/include/autoware/behavior_path_lane_change_module/utils/utils.hpp

-4
Original file line numberDiff line numberDiff line change
@@ -104,10 +104,6 @@ bool path_footprint_exceeds_target_lane_bound(
104104
const CommonDataPtr & common_data_ptr, const PathWithLaneId & path, const VehicleInfo & ego_info,
105105
const double margin = 0.1);
106106

107-
std::vector<DrivableLanes> generateDrivableLanes(
108-
const std::vector<DrivableLanes> & original_drivable_lanes, const RouteHandler & route_handler,
109-
const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & lane_change_lanes);
110-
111107
std::vector<DrivableLanes> generateDrivableLanes(
112108
const RouteHandler & route_handler, const lanelet::ConstLanelets & current_lanes,
113109
const lanelet::ConstLanelets & lane_change_lanes);

planning/behavior_path_planner/autoware_behavior_path_lane_change_module/src/utils/utils.cpp

-119
Original file line numberDiff line numberDiff line change
@@ -206,125 +206,6 @@ std::vector<DrivableLanes> generateDrivableLanes(
206206
return drivable_lanes;
207207
}
208208

209-
std::vector<DrivableLanes> generateDrivableLanes(
210-
const std::vector<DrivableLanes> & original_drivable_lanes, const RouteHandler & route_handler,
211-
const lanelet::ConstLanelets & current_lanes, const lanelet::ConstLanelets & lane_change_lanes)
212-
{
213-
const auto has_same_lane =
214-
[](const lanelet::ConstLanelets & lanes, const lanelet::ConstLanelet & lane) {
215-
if (lanes.empty()) return false;
216-
const auto has_same = [&](const auto & ll) { return ll.id() == lane.id(); };
217-
return std::find_if(lanes.begin(), lanes.end(), has_same) != lanes.end();
218-
};
219-
220-
const auto check_middle = [&](const auto & lane) -> std::optional<DrivableLanes> {
221-
for (const auto & drivable_lane : original_drivable_lanes) {
222-
if (has_same_lane(drivable_lane.middle_lanes, lane)) {
223-
return drivable_lane;
224-
}
225-
}
226-
return std::nullopt;
227-
};
228-
229-
const auto check_left = [&](const auto & lane) -> std::optional<DrivableLanes> {
230-
for (const auto & drivable_lane : original_drivable_lanes) {
231-
if (drivable_lane.left_lane.id() == lane.id()) {
232-
return drivable_lane;
233-
}
234-
}
235-
return std::nullopt;
236-
};
237-
238-
const auto check_right = [&](const auto & lane) -> std::optional<DrivableLanes> {
239-
for (const auto & drivable_lane : original_drivable_lanes) {
240-
if (drivable_lane.right_lane.id() == lane.id()) {
241-
return drivable_lane;
242-
}
243-
}
244-
return std::nullopt;
245-
};
246-
247-
size_t current_lc_idx = 0;
248-
std::vector<DrivableLanes> drivable_lanes(current_lanes.size());
249-
for (size_t i = 0; i < current_lanes.size(); ++i) {
250-
const auto & current_lane = current_lanes.at(i);
251-
252-
const auto middle_drivable_lane = check_middle(current_lane);
253-
if (middle_drivable_lane) {
254-
drivable_lanes.at(i) = *middle_drivable_lane;
255-
}
256-
257-
const auto left_drivable_lane = check_left(current_lane);
258-
if (left_drivable_lane) {
259-
drivable_lanes.at(i) = *left_drivable_lane;
260-
}
261-
262-
const auto right_drivable_lane = check_right(current_lane);
263-
if (right_drivable_lane) {
264-
drivable_lanes.at(i) = *right_drivable_lane;
265-
}
266-
267-
if (!middle_drivable_lane && !left_drivable_lane && !right_drivable_lane) {
268-
drivable_lanes.at(i).left_lane = current_lane;
269-
drivable_lanes.at(i).right_lane = current_lane;
270-
}
271-
272-
const auto left_lane = route_handler.getLeftLanelet(current_lane);
273-
const auto right_lane = route_handler.getRightLanelet(current_lane);
274-
if (!left_lane && !right_lane) {
275-
continue;
276-
}
277-
278-
for (size_t lc_idx = current_lc_idx; lc_idx < lane_change_lanes.size(); ++lc_idx) {
279-
const auto & lc_lane = lane_change_lanes.at(lc_idx);
280-
if (left_lane && lc_lane.id() == left_lane->id()) {
281-
if (left_drivable_lane) {
282-
drivable_lanes.at(i).left_lane = lc_lane;
283-
}
284-
current_lc_idx = lc_idx;
285-
break;
286-
}
287-
288-
if (right_lane && lc_lane.id() == right_lane->id()) {
289-
if (right_drivable_lane) {
290-
drivable_lanes.at(i).right_lane = lc_lane;
291-
}
292-
current_lc_idx = lc_idx;
293-
break;
294-
}
295-
}
296-
}
297-
298-
for (size_t i = current_lc_idx + 1; i < lane_change_lanes.size(); ++i) {
299-
const auto & lc_lane = lane_change_lanes.at(i);
300-
DrivableLanes drivable_lane;
301-
302-
const auto middle_drivable_lane = check_middle(lc_lane);
303-
if (middle_drivable_lane) {
304-
drivable_lane = *middle_drivable_lane;
305-
}
306-
307-
const auto left_drivable_lane = check_left(lc_lane);
308-
if (left_drivable_lane) {
309-
drivable_lane = *left_drivable_lane;
310-
}
311-
312-
const auto right_drivable_lane = check_right(lc_lane);
313-
if (right_drivable_lane) {
314-
drivable_lane = *right_drivable_lane;
315-
}
316-
317-
if (!middle_drivable_lane && !left_drivable_lane && !right_drivable_lane) {
318-
drivable_lane.left_lane = lc_lane;
319-
drivable_lane.right_lane = lc_lane;
320-
}
321-
322-
drivable_lanes.push_back(drivable_lane);
323-
}
324-
325-
return drivable_lanes;
326-
}
327-
328209
double getLateralShift(const LaneChangePath & path)
329210
{
330211
if (path.shifted_path.shift_length.empty()) {

0 commit comments

Comments
 (0)