Skip to content

Commit

Permalink
perf(costmap_generator, scenario_selector): faster getLinkedParkingLot (
Browse files Browse the repository at this point in the history
#7930)

Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
  • Loading branch information
maxime-clem authored Jul 22, 2024
1 parent 802d05d commit cfbd0cf
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -95,11 +95,9 @@ std::shared_ptr<lanelet::ConstPolygon3d> findNearestParkinglot(
const std::shared_ptr<lanelet::LaneletMap> & lanelet_map_ptr,
const lanelet::BasicPoint2d & current_position)
{
const auto all_parking_lots = lanelet::utils::query::getAllParkingLots(lanelet_map_ptr);

const auto linked_parking_lot = std::make_shared<lanelet::ConstPolygon3d>();
const auto result = lanelet::utils::query::getLinkedParkingLot(
current_position, all_parking_lots, linked_parking_lot.get());
current_position, lanelet_map_ptr, linked_parking_lot.get());

if (result) {
return linked_parking_lot;
Expand Down
4 changes: 1 addition & 3 deletions planning/autoware_scenario_selector/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,11 +37,9 @@ std::shared_ptr<lanelet::ConstPolygon3d> findNearestParkinglot(
const std::shared_ptr<lanelet::LaneletMap> & lanelet_map_ptr,
const lanelet::BasicPoint2d & current_position)
{
const auto all_parking_lots = lanelet::utils::query::getAllParkingLots(lanelet_map_ptr);

const auto linked_parking_lot = std::make_shared<lanelet::ConstPolygon3d>();
const auto result = lanelet::utils::query::getLinkedParkingLot(
current_position, all_parking_lots, linked_parking_lot.get());
current_position, lanelet_map_ptr, linked_parking_lot.get());

if (result) {
return linked_parking_lot;
Expand Down

0 comments on commit cfbd0cf

Please sign in to comment.