PointsTooClose.cpp
Go to the documentation of this file.
2 
3 #include <lanelet2_core/geometry/Point.h>
4 
6 
7 namespace lanelet {
8 namespace validation {
9 namespace {
10 RegisterMapValidator<PointsTooCloseChecker> reg;
11 } // namespace
12 
14  Issues issues;
15  for (const auto& p : map.pointLayer) {
16  auto nearest = map.pointLayer.nearest(utils::to2D(p).basicPoint(), 2);
17  if (nearest.size() == 2) {
18  auto& next = nearest[0] == p ? nearest[1] : nearest[0];
19  if (geometry::distance(p, next) < 0.05) {
20  issues.emplace_back(
22  "Point is very close to point " + std::to_string(next.id()) + ". This can lead to defects in the map");
23  }
24  }
25  }
26  return issues;
27 }
28 
29 } // namespace validation
30 } // namespace lanelet
lanelet
next
Optional< ConstLaneletOrArea > next
lanelet::LaneletMapLayers::pointLayer
PointLayer pointLayer
p
BasicPoint p
lanelet::validation::Primitive::Point
@ Point
lanelet::validation::Issues
std::vector< Issue > Issues
Definition: Issue.h:65
lanelet::LaneletMap
lanelet::validation::Severity::Warning
@ Warning
lanelet::validation::PointsTooCloseChecker::operator()
Issues operator()(const LaneletMap &map) override
Definition: PointsTooClose.cpp:13
PointsTooClose.h
lanelet::PrimitiveLayer::nearest
PrimitiveVec nearest(const BasicPoint2d &point, unsigned n)
ValidatorFactory.h


lanelet2_validation
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:26:17