BasicValidator.h
Go to the documentation of this file.
1 #pragma once
4 
5 #include <memory>
6 
8 
9 namespace lanelet {
10 namespace routing {
11 class RoutingGraph;
12 } // namespace routing
13 
14 namespace validation {
15 
17 class MapValidator { // NOLINT
18  public:
19  virtual ~MapValidator() = default;
20  constexpr static const char* name() { return ""; }
21  virtual Issues operator()(const LaneletMap& map) = 0;
22 };
23 using MapValidatorUPtr = std::unique_ptr<MapValidator>;
24 using MapValidatorUPtrs = std::vector<MapValidatorUPtr>;
25 
29 class TrafficRuleValidator { // NOLINT
30  public:
31  constexpr static const char* name() { return ""; }
32  virtual Issues operator()(const LaneletMap& map, const std::vector<traffic_rules::TrafficRulesUPtr>& rules) = 0;
33  virtual ~TrafficRuleValidator() = default;
34 };
35 using TrafficRuleValidatorUPtr = std::unique_ptr<TrafficRuleValidator>;
36 using TrafficRuleValidatorUPtrs = std::vector<TrafficRuleValidatorUPtr>;
37 
39 class RoutingGraphValidator { // NOLINTs
40  public:
41  constexpr static const char* name() { return ""; }
43  virtual Issues operator()(const routing::RoutingGraph& graph, const traffic_rules::TrafficRules& rules) = 0;
44  virtual ~RoutingGraphValidator() = default;
45 };
46 using RoutingGraphValidatorUPtr = std::unique_ptr<RoutingGraphValidator>;
47 using RoutingGraphValidatorUPtrs = std::vector<RoutingGraphValidatorUPtr>;
48 
49 } // namespace validation
50 } // namespace lanelet
std::unique_ptr< TrafficRuleValidator > TrafficRuleValidatorUPtr
static constexpr const char * name()
static constexpr const char * name()
A routing graph validator works similar, but instead uses the routing graph of a map to detect issues...
std::vector< Issue > Issues
Definition: Issue.h:65
std::unique_ptr< MapValidator > MapValidatorUPtr
std::vector< RoutingGraphValidatorUPtr > RoutingGraphValidatorUPtrs
std::unique_ptr< RoutingGraphValidator > RoutingGraphValidatorUPtr
std::vector< TrafficRuleValidatorUPtr > TrafficRuleValidatorUPtrs
Most simple form of a validator. It gets a map once and reports errors.
std::vector< MapValidatorUPtr > MapValidatorUPtrs
static constexpr const char * name()


lanelet2_validation
Author(s): Fabian Poggenhans
autogenerated on Tue Jun 6 2023 02:24:02