Skip to content

Commit 90722d8

Browse files
committed
perf(costmap_generator, scenario_selector): faster getLinkedParkingLot
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
1 parent 5e5ad0b commit 90722d8

File tree

2 files changed

+2
-6
lines changed

2 files changed

+2
-6
lines changed

planning/autoware_costmap_generator/nodes/autoware_costmap_generator/costmap_generator_node.cpp

+1-3
Original file line numberDiff line numberDiff line change
@@ -95,11 +95,9 @@ std::shared_ptr<lanelet::ConstPolygon3d> findNearestParkinglot(
9595
const std::shared_ptr<lanelet::LaneletMap> & lanelet_map_ptr,
9696
const lanelet::BasicPoint2d & current_position)
9797
{
98-
const auto all_parking_lots = lanelet::utils::query::getAllParkingLots(lanelet_map_ptr);
99-
10098
const auto linked_parking_lot = std::make_shared<lanelet::ConstPolygon3d>();
10199
const auto result = lanelet::utils::query::getLinkedParkingLot(
102-
current_position, all_parking_lots, linked_parking_lot.get());
100+
current_position, lanelet_map_ptr, linked_parking_lot.get());
103101

104102
if (result) {
105103
return linked_parking_lot;

planning/autoware_scenario_selector/src/node.cpp

+1-3
Original file line numberDiff line numberDiff line change
@@ -37,11 +37,9 @@ std::shared_ptr<lanelet::ConstPolygon3d> findNearestParkinglot(
3737
const std::shared_ptr<lanelet::LaneletMap> & lanelet_map_ptr,
3838
const lanelet::BasicPoint2d & current_position)
3939
{
40-
const auto all_parking_lots = lanelet::utils::query::getAllParkingLots(lanelet_map_ptr);
41-
4240
const auto linked_parking_lot = std::make_shared<lanelet::ConstPolygon3d>();
4341
const auto result = lanelet::utils::query::getLinkedParkingLot(
44-
current_position, all_parking_lots, linked_parking_lot.get());
42+
current_position, lanelet_map_ptr, linked_parking_lot.get());
4543

4644
if (result) {
4745
return linked_parking_lot;

0 commit comments

Comments
 (0)