Commit 90722d8 1 parent 5e5ad0b commit 90722d8 Copy full SHA for 90722d8
File tree 2 files changed +2
-6
lines changed
autoware_costmap_generator/nodes/autoware_costmap_generator
autoware_scenario_selector/src
2 files changed +2
-6
lines changed Original file line number Diff line number Diff line change @@ -95,11 +95,9 @@ std::shared_ptr<lanelet::ConstPolygon3d> findNearestParkinglot(
95
95
const std::shared_ptr<lanelet::LaneletMap> & lanelet_map_ptr,
96
96
const lanelet::BasicPoint2d & current_position)
97
97
{
98
- const auto all_parking_lots = lanelet::utils::query::getAllParkingLots (lanelet_map_ptr);
99
-
100
98
const auto linked_parking_lot = std::make_shared<lanelet::ConstPolygon3d>();
101
99
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 ());
103
101
104
102
if (result) {
105
103
return linked_parking_lot;
Original file line number Diff line number Diff line change @@ -37,11 +37,9 @@ std::shared_ptr<lanelet::ConstPolygon3d> findNearestParkinglot(
37
37
const std::shared_ptr<lanelet::LaneletMap> & lanelet_map_ptr,
38
38
const lanelet::BasicPoint2d & current_position)
39
39
{
40
- const auto all_parking_lots = lanelet::utils::query::getAllParkingLots (lanelet_map_ptr);
41
-
42
40
const auto linked_parking_lot = std::make_shared<lanelet::ConstPolygon3d>();
43
41
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 ());
45
43
46
44
if (result) {
47
45
return linked_parking_lot;
You can’t perform that action at this time.
0 commit comments