Validation.cpp
Go to the documentation of this file.
2 
4 #include <lanelet2_io/Io.h>
8 
10 
11 namespace lanelet {
12 namespace validation {
13 namespace {
14 Regexes parseFilterString(const std::string& str) {
15  Regexes regexes;
16  std::stringstream ss(str);
17 
18  while (ss.good()) {
19  std::string substr;
20  getline(ss, substr, ',');
21  if (substr.empty()) {
22  continue;
23  }
24  regexes.emplace_back(substr, std::regex::basic | std::regex::icase);
25  }
26  return regexes;
27 }
28 
29 template <typename Container1T, typename Container2T>
30 void append(Container1T& to, Container2T&& from) {
31  to.insert(to.end(), std::make_move_iterator(from.begin()), std::make_move_iterator(from.end()));
32 }
33 
34 template <typename ValidatorT, typename Func>
35 std::vector<DetectedIssues> runValidators(const ValidatorsWithName<ValidatorT>& validators, Func f) {
36  std::vector<DetectedIssues> issues;
37  issues.reserve(validators.size());
38  for (auto& validator : validators) {
39  auto foundIssues = f(*validator.second);
40  if (!foundIssues.empty()) {
41  issues.emplace_back(validator.first, std::move(foundIssues));
42  }
43  }
44  return issues;
45 }
46 
47 void runMapValidators(std::vector<DetectedIssues>& issues, const Regexes& regexes, const LaneletMap& map) {
48  auto validators = ValidatorFactory::instance().createMapValidators(regexes);
49  append(issues, runValidators(validators, [&map](auto& validator) { return validator(map); }));
50 }
51 
52 void runRuleValidators(std::vector<DetectedIssues>& issues, const Regexes& regexes, const LaneletMap& map,
53  const std::vector<traffic_rules::TrafficRulesUPtr>& rules) {
54  auto validators = ValidatorFactory::instance().createTrafficRuleValidators(regexes);
55  append(issues, runValidators(validators, [&map, &rules](auto& validator) { return validator(map, rules); }));
56 }
57 
58 void runRoutingGraphValidators(std::vector<DetectedIssues>& issues, const Regexes& regexes, LaneletMap& map,
59  const std::vector<traffic_rules::TrafficRulesUPtr>& rules) {
60  auto routingGraphValidators = ValidatorFactory::instance().createRoutingGraphValidators(regexes);
61  if (routingGraphValidators.empty()) {
62  return;
63  }
64  for (const auto& rule : rules) {
65  routing::RoutingGraphPtr routingGraph;
66  try {
67  routingGraph = routing::RoutingGraph::build(map, *rule);
68  } catch (LaneletError& err) {
69  std::stringstream msg;
70  msg << "Failed to create routing graph for " << *rule << ": " << err.what();
71  issues.emplace_back("general", Issues{Issue(Severity::Error, msg.str())});
72  continue;
73  }
74  append(issues, runValidators(routingGraphValidators,
75  [&routingGraph, &rule](auto& validator) { return validator(*routingGraph, *rule); }));
76  }
77 }
78 } // namespace
79 
81  Issues errors;
82  for (const auto& issue : issues) {
83  if (issue.severity == Severity::Error) {
84  errors.push_back(issue);
85  }
86  }
87  return errors;
88 }
89 
91  Issues warning;
92  for (const auto& issue : issues) {
93  if (issue.severity == Severity::Warning) {
94  warning.push_back(issue);
95  }
96  }
97  return warning;
98 }
99 
100 Strings availabeChecks(const std::string& filterString) {
101  return ValidatorFactory::instance().availableValidators(parseFilterString(filterString));
102 }
103 
104 IssueReport buildReport(std::vector<DetectedIssues> issues) {
105  IssueReport report;
106  for (auto& issue : issues) {
107  auto buildReports = [&check = issue.checkName](auto& issue) { return issue.buildReport() + " [" + check + "]"; };
108  auto errorsFromCheck = utils::transform(issue.errors(), buildReports);
109  if (!errorsFromCheck.empty()) {
110  report.errors.insert(report.errors.end(), errorsFromCheck.begin(), errorsFromCheck.end());
111  }
112  auto warningsFromCheck = utils::transform(issue.warnings(), buildReports);
113  if (!warningsFromCheck.empty()) {
114  report.warnings.insert(report.warnings.end(), warningsFromCheck.begin(), warningsFromCheck.end());
115  }
116  }
117  return report;
118 }
119 
120 std::vector<DetectedIssues> validateMap(LaneletMap& map, const ValidationConfig& config) {
121  std::vector<DetectedIssues> issues;
122  Regexes regexes = parseFilterString(config.checksFilter);
123 
124  runMapValidators(issues, regexes, map);
125 
126  auto trafficRules = utils::transform(config.participants, [&config](auto& participant) {
127  return traffic_rules::TrafficRulesFactory::create(config.location, participant);
128  });
129 
130  runRuleValidators(issues, regexes, map, trafficRules);
131  runRoutingGraphValidators(issues, regexes, map, trafficRules);
132  return issues;
133 }
134 
135 std::vector<DetectedIssues> validateMap(const std::string& mapFilename, const ValidationConfig& config) {
136  using namespace std::string_literals;
137  auto checks = parseFilterString(config.checksFilter);
138  auto projector = lanelet::projection::UtmProjector(Origin{config.origin});
139  std::vector<DetectedIssues> issues;
140  LaneletMapPtr map;
141  try {
142  Strings errors;
143  map = lanelet::load(mapFilename, projector, &errors);
144  if (!errors.empty()) {
145  issues.emplace_back("general",
146  utils::transform(errors, [](auto& error) { return Issue(Severity::Error, error); }));
147  }
148  } catch (lanelet::LaneletError& err) {
149  return {{"general", {Issue(Severity::Error, "Failed to load map: "s + err.what())}}};
150  }
151  append(issues, validateMap(*map, config));
152  return issues;
153 }
154 
155 } // namespace validation
156 } // namespace lanelet
lanelet::validation::buildReport
IssueReport buildReport(std::vector< DetectedIssues > issues)
Generates the issue report.
Definition: Validation.cpp:104
lanelet::validation::ValidationConfig::participants
Strings participants
Definition: Validation.h:26
UTM.h
lanelet::LaneletMapPtr
std::shared_ptr< LaneletMap > LaneletMapPtr
lanelet
GPSPoint.h
lanelet::validation::ValidationConfig
Configuration object for the validation.
Definition: Validation.h:23
TrafficRulesFactory.h
lanelet::validation::ValidationConfig::checksFilter
std::string checksFilter
Definition: Validation.h:24
lanelet::routing::RoutingGraph::build
static RoutingGraphUPtr build(const LaneletMap &laneletMap, const traffic_rules::TrafficRules &trafficRules, const RoutingCostPtrs &routingCosts=defaultRoutingCosts(), const Configuration &config=Configuration())
lanelet::validation::Regexes
std::vector< std::regex > Regexes
Definition: ValidatorFactory.h:12
lanelet::validation::DetectedIssues::issues
Issues issues
Definition: Validation.h:19
Io.h
lanelet::validation::Strings
std::vector< std::string > Strings
Definition: Validation.h:10
lanelet::projection::UtmProjector
lanelet::validation::IssueReport::warnings
Strings warnings
Definition: Validation.h:32
lanelet::validation::ValidatorFactory::createTrafficRuleValidators
ValidatorsWithName< TrafficRuleValidator > createTrafficRuleValidators(const Regexes &regexes)
Definition: ValidatorFactory.cpp:50
lanelet::validation::availabeChecks
Strings availabeChecks(const std::string &filterString)
Reports the available checks for the given filter. Empty will return all.
Definition: Validation.cpp:100
lanelet::validation::Issues
std::vector< Issue > Issues
Definition: Issue.h:65
lanelet::utils::transform
auto transform(Container &&c, Func f)
lanelet::LaneletMap
lanelet::validation::validateMap
std::vector< DetectedIssues > validateMap(LaneletMap &map, const ValidationConfig &config)
Definition: Validation.cpp:120
lanelet::validation::DetectedIssues::warnings
Issues warnings() const
Definition: Validation.cpp:90
lanelet::validation::ValidationConfig::origin
GPSPoint origin
Definition: Validation.h:27
lanelet::routing::RoutingGraphPtr
std::shared_ptr< RoutingGraph > RoutingGraphPtr
lanelet::load
std::unique_ptr< LaneletMap > load(const std::string &filename, const Origin &origin=Origin::defaultOrigin(), ErrorMessages *errors=nullptr, const io::Configuration &params=io::Configuration())
lanelet::validation::Severity::Warning
@ Warning
lanelet::validation::ValidatorFactory::instance
static ValidatorFactory & instance()
Definition: ValidatorFactory.cpp:41
lanelet::Origin
lanelet::validation::ValidatorFactory::availableValidators
std::vector< std::string > availableValidators(const Regexes &regexes={})
returns all available parsers as vector
Definition: ValidatorFactory.cpp:58
Validation.h
lanelet::validation::ValidatorFactory::createRoutingGraphValidators
ValidatorsWithName< RoutingGraphValidator > createRoutingGraphValidators(const Regexes &regexes)
Definition: ValidatorFactory.cpp:54
lanelet::validation::Severity::Error
@ Error
lanelet::validation::DetectedIssues::errors
Issues errors() const
Definition: Validation.cpp:80
ValidatorFactory.h
lanelet::validation::ValidatorFactory::createMapValidators
ValidatorsWithName< MapValidator > createMapValidators(const Regexes &regexes)
Definition: ValidatorFactory.cpp:46
lanelet::LaneletError
lanelet::validation::Issue
Definition: Issue.h:44
lanelet::validation::IssueReport::errors
Strings errors
Definition: Validation.h:33
RoutingGraph.h
lanelet::validation::IssueReport
Contains each warning/error as formatted strings.
Definition: Validation.h:31


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