Skip to content

Commit

Permalink
refactor(static_drivable_area_expansion): remove unused arg
Browse files Browse the repository at this point in the history
Signed-off-by: satoshi-ota <satoshi.ota928@gmail.com>
  • Loading branch information
satoshi-ota committed Dec 31, 2023
1 parent f28caf7 commit 3c46099
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 6 deletions.
7 changes: 3 additions & 4 deletions planning/behavior_path_planner/src/planner_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -225,8 +225,7 @@ void PlannerManager::generateCombinedDrivableArea(
} else if (di.is_already_expanded) {
// for single side shift
utils::generateDrivableArea(
output.path, di.drivable_lanes, false, false, false, data->parameters.vehicle_length, data,
is_driving_forward);
output.path, di.drivable_lanes, false, false, false, data, is_driving_forward);
} else {
const auto shorten_lanes = utils::cutOverlappedLanes(output.path, di.drivable_lanes);

Expand All @@ -238,8 +237,8 @@ void PlannerManager::generateCombinedDrivableArea(
// for other modules where multiple modules may be launched
utils::generateDrivableArea(
output.path, expanded_lanes, di.enable_expanding_hatched_road_markings,
di.enable_expanding_intersection_areas, di.enable_expanding_freespace_areas,
data->parameters.vehicle_length, data, is_driving_forward);
di.enable_expanding_intersection_areas, di.enable_expanding_freespace_areas, data,
is_driving_forward);
}

// extract obstacles from drivable area
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ std::vector<DrivableLanes> getNonOverlappingExpandedLanes(
void generateDrivableArea(
PathWithLaneId & path, const std::vector<DrivableLanes> & lanes,
const bool enable_expanding_hatched_road_markings, const bool enable_expanding_intersection_areas,
const bool enable_expanding_freespace_areas, const double vehicle_length,
const bool enable_expanding_freespace_areas,
const std::shared_ptr<const PlannerData> planner_data, const bool is_driving_forward = true);

void generateDrivableArea(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -729,7 +729,7 @@ std::vector<DrivableLanes> getNonOverlappingExpandedLanes(
void generateDrivableArea(
PathWithLaneId & path, const std::vector<DrivableLanes> & lanes,
const bool enable_expanding_hatched_road_markings, const bool enable_expanding_intersection_areas,
const bool enable_expanding_freespace_areas, [[maybe_unused]] const double vehicle_length,
const bool enable_expanding_freespace_areas,
const std::shared_ptr<const PlannerData> planner_data, const bool is_driving_forward)
{
if (path.points.empty()) {
Expand Down

0 comments on commit 3c46099

Please sign in to comment.