12 namespace validation {
14 Regexes parseFilterString(
const std::string& str) {
16 std::stringstream ss(str);
20 getline(ss, substr,
',');
24 regexes.emplace_back(substr, std::regex::basic | std::regex::icase);
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()));
34 template <
typename Val
idatorT,
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));
47 void runMapValidators(std::vector<DetectedIssues>& issues,
const Regexes& regexes,
const LaneletMap& map) {
49 append(issues, runValidators(validators, [&map](
auto& validator) {
return validator(map); }));
52 void runRuleValidators(std::vector<DetectedIssues>& issues,
const Regexes& regexes,
const LaneletMap& map,
53 const std::vector<traffic_rules::TrafficRulesUPtr>& rules) {
55 append(issues, runValidators(validators, [&map, &rules](
auto& validator) {
return validator(map, rules); }));
58 void runRoutingGraphValidators(std::vector<DetectedIssues>& issues,
const Regexes& regexes, LaneletMap& map,
59 const std::vector<traffic_rules::TrafficRulesUPtr>& rules) {
61 if (routingGraphValidators.empty()) {
64 for (
const auto& rule : rules) {
68 }
catch (LaneletError& err) {
69 std::stringstream msg;
70 msg <<
"Failed to create routing graph for " << *rule <<
": " << err.what();
74 append(issues, runValidators(routingGraphValidators,
75 [&routingGraph, &rule](
auto& validator) {
return validator(*routingGraph, *rule); }));
82 for (
const auto& issue :
issues) {
92 for (
const auto& issue :
issues) {
94 warning.push_back(issue);
106 for (
auto& issue : issues) {
107 auto buildReports = [&check = issue.checkName](
auto& issue) {
return issue.buildReport() +
" [" + check +
"]"; };
109 if (!errorsFromCheck.empty()) {
110 report.
errors.insert(report.
errors.end(), errorsFromCheck.begin(), errorsFromCheck.end());
113 if (!warningsFromCheck.empty()) {
114 report.
warnings.insert(report.
warnings.end(), warningsFromCheck.begin(), warningsFromCheck.end());
121 std::vector<DetectedIssues> issues;
124 runMapValidators(issues, regexes, map);
127 return traffic_rules::TrafficRulesFactory::create(config.location, participant);
130 runRuleValidators(issues, regexes, map, trafficRules);
131 runRoutingGraphValidators(issues, regexes, map, trafficRules);
136 using namespace std::string_literals;
139 std::vector<DetectedIssues> issues;
144 if (!errors.empty()) {
145 issues.emplace_back(
"general",