Skip to content

Commit d4cb23c

Browse files
authored
perf(lanelet2_map_preprocessor): use set.find instead of std::find (#7033)
Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
1 parent de53828 commit d4cb23c

5 files changed

+4
-19
lines changed

map/util/lanelet2_map_preprocessor/src/fix_lane_change_tags.cpp

-5
Original file line numberDiff line numberDiff line change
@@ -48,11 +48,6 @@ bool loadLaneletMap(
4848
return true;
4949
}
5050

51-
bool exists(std::unordered_set<lanelet::Id> & set, lanelet::Id element)
52-
{
53-
return std::find(set.begin(), set.end(), element) != set.end();
54-
}
55-
5651
lanelet::Lanelets convertToVector(lanelet::LaneletMapPtr & lanelet_map_ptr)
5752
{
5853
lanelet::Lanelets lanelets;

map/util/lanelet2_map_preprocessor/src/fix_z_value_by_pcd.cpp

+2-7
Original file line numberDiff line numberDiff line change
@@ -91,11 +91,6 @@ double getMinHeightAroundPoint(
9191
return min_height;
9292
}
9393

94-
bool exists(std::unordered_set<lanelet::Id> & set, lanelet::Id element)
95-
{
96-
return std::find(set.begin(), set.end(), element) != set.end();
97-
}
98-
9994
void adjustHeight(
10095
const pcl::PointCloud<pcl::PointXYZ>::Ptr & pcd_map_ptr, lanelet::LaneletMapPtr & lanelet_map_ptr)
10196
{
@@ -108,7 +103,7 @@ void adjustHeight(
108103

109104
for (lanelet::Lanelet & llt : lanelet_map_ptr->laneletLayer) {
110105
for (lanelet::Point3d & pt : llt.leftBound()) {
111-
if (exists(done, pt.id())) {
106+
if (done.find(pt.id()) != done.end()) {
112107
continue;
113108
}
114109
pcl::PointXYZ pcl_pt;
@@ -122,7 +117,7 @@ void adjustHeight(
122117
done.insert(pt.id());
123118
}
124119
for (lanelet::Point3d & pt : llt.rightBound()) {
125-
if (exists(done, pt.id())) {
120+
if (done.find(pt.id()) != done.end()) {
126121
continue;
127122
}
128123
pcl::PointXYZ pcl_pt;

map/util/lanelet2_map_preprocessor/src/merge_close_lines.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ bool loadLaneletMap(
4949

5050
bool exists(std::unordered_set<lanelet::Id> & set, lanelet::Id element)
5151
{
52-
return std::find(set.begin(), set.end(), element) != set.end();
52+
return set.find(element) != set.end();
5353
}
5454

5555
lanelet::LineStrings3d convertLineLayerToLineStrings(lanelet::LaneletMapPtr & lanelet_map_ptr)

map/util/lanelet2_map_preprocessor/src/merge_close_points.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ bool loadLaneletMap(
4545

4646
bool exists(std::unordered_set<lanelet::Id> & set, lanelet::Id element)
4747
{
48-
return std::find(set.begin(), set.end(), element) != set.end();
48+
return set.find(element) != set.end();
4949
}
5050

5151
lanelet::Points3d convertPointsLayerToPoints(lanelet::LaneletMapPtr & lanelet_map_ptr)

map/util/lanelet2_map_preprocessor/src/remove_unreferenced_geometry.cpp

-5
Original file line numberDiff line numberDiff line change
@@ -43,11 +43,6 @@ bool loadLaneletMap(
4343
return true;
4444
}
4545

46-
bool exists(std::unordered_set<lanelet::Id> & set, lanelet::Id element)
47-
{
48-
return std::find(set.begin(), set.end(), element) != set.end();
49-
}
50-
5146
lanelet::Points3d convertPointsLayerToPoints(lanelet::LaneletMapPtr & lanelet_map_ptr)
5247
{
5348
lanelet::Points3d points;

0 commit comments

Comments
 (0)