Skip to content
This repository has been archived by the owner on Jul 1, 2024. It is now read-only.

perf(lanelet2_extension): more efficient getLinkedParkingLot #248

Open
wants to merge 1 commit into
base: main
Choose a base branch
from
Open
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 @@ -189,7 +189,7 @@ bool getLinkedParkingLot(
lanelet::ConstPolygon3d * linked_parking_lot);
// get linked parking lot from current pose of ego car
bool getLinkedParkingLot(
const lanelet::BasicPoint2d & current_position, const lanelet::ConstPolygons3d & all_parking_lots,
const lanelet::BasicPoint2d & current_position, const lanelet::LaneletMapPtr & lanelet_map_ptr,
lanelet::ConstPolygon3d * linked_parking_lot);
// get linked parking lot from parking space
bool getLinkedParkingLot(
Expand Down
19 changes: 12 additions & 7 deletions tmp/lanelet2_extension/lib/query.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -591,15 +591,20 @@

// get overlapping parking lot
bool query::getLinkedParkingLot(
const lanelet::BasicPoint2d & current_position, const lanelet::ConstPolygons3d & all_parking_lots,
const lanelet::BasicPoint2d & current_position, const lanelet::LaneletMapPtr & lanelet_map_ptr,
lanelet::ConstPolygon3d * linked_parking_lot)
{
for (const auto & parking_lot : all_parking_lots) {
const double distance =
boost::geometry::distance(current_position, to2D(parking_lot).basicPolygon());
if (distance < std::numeric_limits<double>::epsilon()) {
*linked_parking_lot = parking_lot;
return true;
const auto candidates =
lanelet_map_ptr->polygonLayer.search(lanelet::geometry::boundingBox2d(current_position));

Check warning on line 598 in tmp/lanelet2_extension/lib/query.cpp

View check run for this annotation

Codecov / codecov/patch

tmp/lanelet2_extension/lib/query.cpp#L598

Added line #L598 was not covered by tests
for (const auto & candidate : candidates) {
const std::string type = candidate.attributeOr(lanelet::AttributeName::Type, "none");
if (type == "parking_lot") {
const double distance =
boost::geometry::distance(current_position, to2D(candidate).basicPolygon());
if (distance < std::numeric_limits<double>::epsilon()) {
*linked_parking_lot = candidate;
return true;
}
}
}
return false;
Expand Down
6 changes: 3 additions & 3 deletions tmp/lanelet2_extension_python/src/utility.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -209,11 +209,11 @@
}

lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
const lanelet::BasicPoint2d & current_position, const lanelet::ConstPolygons3d & all_parking_lots)
const lanelet::BasicPoint2d & current_position, const lanelet::LaneletMapPtr lanelet_map_ptr)
{
lanelet::ConstPolygon3d linked_parking_lot;
if (lanelet::utils::query::getLinkedParkingLot(
current_position, all_parking_lots, &linked_parking_lot)) {
current_position, lanelet_map_ptr, &linked_parking_lot)) {
return linked_parking_lot;
} else {
return {};
Expand Down Expand Up @@ -506,7 +506,7 @@
const lanelet::ConstLanelet &, const lanelet::ConstPolygons3d &)>(
"getLinkedParkingLot", ::getLinkedParkingLot);
bp::def<lanelet::Optional<lanelet::ConstPolygon3d>(
const lanelet::BasicPoint2d &, const lanelet::ConstPolygons3d &)>(
const lanelet::BasicPoint2d &, const lanelet::LaneletMapPtr)>(

Check warning on line 509 in tmp/lanelet2_extension_python/src/utility.cpp

View check run for this annotation

Codecov / codecov/patch

tmp/lanelet2_extension_python/src/utility.cpp#L509

Added line #L509 was not covered by tests
"getLinkedParkingLot", ::getLinkedParkingLot);
bp::def<lanelet::Optional<lanelet::ConstPolygon3d>(
const lanelet::ConstLineString3d &, const lanelet::ConstPolygons3d &)>(
Expand Down
Loading