CurvatureTooBig.cpp
Go to the documentation of this file.
2 
3 #include <lanelet2_core/geometry/LineString.h>
4 
5 #include <iostream>
6 
8 
9 namespace lanelet {
10 namespace validation {
11 namespace {
12 RegisterMapValidator<CurvatureTooBigChecker> reg1;
13 } // namespace
14 
16  Issues issues;
17  for (const auto& lanelet : map.laneletLayer) {
18  checkCurvature(issues, utils::to2D(lanelet.leftBound()), lanelet.id());
19  checkCurvature(issues, utils::to2D(lanelet.rightBound()), lanelet.id());
20  }
21  return issues;
22 }
23 
24 void CurvatureTooBigChecker::checkCurvature(Issues& issues, const ConstLineString2d& line, const Id& laneletId) {
25  auto lineHyb = utils::toHybrid(line);
26  if (lineHyb.size() >= 3) {
27  for (size_t i = 1; i < lineHyb.size() - 1; ++i) {
28  if (std::fabs(geometry::curvature2d(lineHyb[i - 1], lineHyb[i], lineHyb[i + 1])) > 0.5) {
29  issues.emplace_back(Severity::Warning, Primitive::Lanelet, laneletId,
30  "Curvature at point " + std::to_string(line[i].id()) +
31  " is bigger than 0.5. This can confuse algorithms using this map.");
32  }
33  }
34  }
35 }
36 
37 } // namespace validation
38 } // namespace lanelet
lanelet::LaneletMapLayers::laneletLayer
LaneletLayer laneletLayer
lanelet::validation::CurvatureTooBigChecker::checkCurvature
static void checkCurvature(Issues &issues, const ConstLineString2d &line, const Id &laneletId)
Definition: CurvatureTooBig.cpp:24
lanelet
lanelet::Id
int64_t Id
lanelet::ConstLineString2d
lanelet::validation::Issues
std::vector< Issue > Issues
Definition: Issue.h:65
lanelet::LaneletMap
lanelet::validation::Primitive::Lanelet
@ Lanelet
CurvatureTooBig.h
lanelet::validation::Severity::Warning
@ Warning
lanelet::validation::CurvatureTooBigChecker::operator()
Issues operator()(const LaneletMap &map) override
Definition: CurvatureTooBig.cpp:15
lanelet::geometry::curvature2d
double curvature2d(const Point2dT &p1, const Point2dT &p2, const Point2dT &p3)
ValidatorFactory.h


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