Skip to content

Commit

Permalink
refactor(behavior_path_planner): clean up
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 Jul 11, 2023
1 parent c32ac2b commit 1e60bcb
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 13 deletions.
19 changes: 7 additions & 12 deletions planning/behavior_path_planner/src/utils/avoidance/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1144,23 +1144,18 @@ double extendToRoadShoulderDistanceWithPolygon(
// get expandable polygons for avoidance (e.g. hatched road markings)
std::vector<lanelet::Polygon3d> expandable_polygons;

const auto exist_polygon = [&](const auto & candidate_polygon) {
return std::any_of(
expandable_polygons.begin(), expandable_polygons.end(),
[&](const auto & polygon) { return polygon.id() == candidate_polygon.id(); });
};

if (use_hatched_road_markings) {
for (const auto & point : target_line) {
const auto new_polygon_candidate =
utils::getPolygonByPoint(rh, point, "hatched_road_markings");
if (!new_polygon_candidate) {
continue;
}

bool is_new_polygon{true};
for (const auto & polygon : expandable_polygons) {
if (polygon.id() == new_polygon_candidate->id()) {
is_new_polygon = false;
break;
}
}

if (is_new_polygon) {
if (!!new_polygon_candidate && !exist_polygon(*new_polygon_candidate)) {
expandable_polygons.push_back(*new_polygon_candidate);
}
}
Expand Down
3 changes: 2 additions & 1 deletion planning/behavior_path_planner/src/utils/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1608,7 +1608,8 @@ std::vector<geometry_msgs::msg::Point> calcBound(

// expand drivable area by intersection areas.
const std::string id = bound_lane.attributeOr("intersection_area", "else");
if (enable_expanding_intersection_areas && id != "else") {
const auto use_intersection_area = enable_expanding_intersection_areas && id != "else";
if (use_intersection_area) {
const auto polygon =
route_handler->getLaneletMapPtr()->polygonLayer.get(std::atoi(id.c_str()));

Expand Down

0 comments on commit 1e60bcb

Please sign in to comment.