Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

perf(query): add faster getLinkedParkingLot function #19

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -167,6 +167,10 @@ bool getLinkedParkingLot(
bool getLinkedParkingLot(
const lanelet::BasicPoint2d & current_position, const lanelet::ConstPolygons3d & all_parking_lots,
lanelet::ConstPolygon3d * linked_parking_lot);
bool getLinkedParkingLot(
const lanelet::BasicPoint2d & current_position,
const lanelet::LaneletMapConstPtr & lanelet_map_ptr,
lanelet::ConstPolygon3d * linked_parking_lot);
// get linked parking lot from parking space
bool getLinkedParkingLot(
const lanelet::ConstLineString3d & parking_space,
Expand Down
16 changes: 16 additions & 0 deletions autoware_lanelet2_extension/lib/query.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -549,6 +549,22 @@
}
return false;
}
bool getLinkedParkingLot(

Check warning on line 552 in autoware_lanelet2_extension/lib/query.cpp

View check run for this annotation

Codecov / codecov/patch

autoware_lanelet2_extension/lib/query.cpp#L552

Added line #L552 was not covered by tests
const lanelet::BasicPoint2d & current_position,
const lanelet::LaneletMapConstPtr & lanelet_map_ptr, lanelet::ConstPolygon3d * linked_parking_lot)
{
auto candidates =
lanelet_map_ptr->polygonLayer.search(lanelet::geometry::boundingBox2d(current_position));
candidates.erase(
std::remove_if(

Check warning on line 559 in autoware_lanelet2_extension/lib/query.cpp

View check run for this annotation

Codecov / codecov/patch

autoware_lanelet2_extension/lib/query.cpp#L559

Added line #L559 was not covered by tests
candidates.begin(), candidates.end(),
[](const auto & c) {
const std::string type = c.attributeOr(lanelet::AttributeName::Type, "none");
return type != "parking_lot";

Check warning on line 563 in autoware_lanelet2_extension/lib/query.cpp

View check run for this annotation

Codecov / codecov/patch

autoware_lanelet2_extension/lib/query.cpp#L561-L563

Added lines #L561 - L563 were not covered by tests
}),
candidates.end());
return getLinkedParkingLot(current_position, candidates, linked_parking_lot);
}

// get overlapping parking lot
bool getLinkedParkingLot(
Expand Down
Loading