Cli.cpp
Go to the documentation of this file.
2 
3 #include <boost/program_options.hpp>
4 #include <iostream>
5 
6 namespace po = boost::program_options;
7 
8 namespace lanelet {
9 namespace validation {
10 
11 CommandLineConfig parseCommandLine(int argc, const char* argv[]) {
13  auto& config = cfg.validationConfig;
14  po::options_description desc(
15  "Runs a set of validators on a map. Think of it like a linter. The following checks are available:");
16  desc.add_options()("help,h", "this help message")
17 
18  ("map_file", po::value<std::string>(), "Path to the map to be validated")
19 
20  ("filter,f", po::value(&config.checksFilter),
21  "Comma separated list of regexes to filter the applicable tests. Will run all tests by default. Example: "
22  "routing_graph.* to run all checks for the routing graph")
23 
24  ("location,l", po::value(&config.location)->default_value(config.location),
25  "Location of the map (for instanciating the traffic rules), e.g. de for Germany")
26 
27  ("participants,p", po::value(&config.participants)->composing(),
28  "Participants for which the routing graph will be instanciated (default: vehicle)")
29 
30  ("lat", po::value(&config.origin.lat)->default_value(config.origin.lat),
31  "latitude coordinate of map origin")
32 
33  ("lon", po::value(&config.origin.lon)->default_value(config.origin.lon),
34  "longitude coofdinate of map origin")
35 
36  ("print", "Only print the checks that will be run, but dont run them");
37  po::variables_map vm;
38  po::positional_options_description pos;
39  pos.add("map_file", 1);
40  po::store(po::command_line_parser(argc, argv).options(desc).positional(pos).run(), vm);
41  po::notify(vm);
42  cfg.help = vm.count("help") != 0;
43  cfg.print = vm.count("print") != 0;
44  if (vm.count("map_file") != 0) {
45  cfg.mapFile = vm["map_file"].as<decltype(cfg.mapFile)>();
46  }
47  if (cfg.help) {
48  std::cout << '\n' << desc;
49  } else if (cfg.mapFile.empty() && !cfg.print) {
50  std::cout << "Please pass either a valid file or '--print' or '--help'!\n";
51  }
52  return cfg;
53 }
54 
55 void printAllIssues(const std::vector<DetectedIssues>& issues) {
56  auto allIssues = buildReport(issues);
57  for (auto& issue : allIssues.errors) {
58  std::cerr << issue << '\n';
59  }
60  for (auto& issue : allIssues.warnings) {
61  std::cout << issue << '\n';
62  }
63  std::cout << allIssues.warnings.size() + allIssues.errors.size() << " issues found.\n";
64 }
65 
66 int runFromConfig(const CommandLineConfig& config) {
67  if (config.help) {
68  return 0;
69  }
70  if (config.print) {
71  auto checks = availabeChecks(config.validationConfig.checksFilter);
72  if (checks.empty()) {
73  std::cout << "No checks found matching '" << config.validationConfig.checksFilter << "'\n";
74  } else {
75  std::cout << "Will use following checks:\n";
76  for (auto& check : checks) {
77  std::cout << check << '\n';
78  }
79  }
80  return 0;
81  }
82  if (config.mapFile.empty()) {
83  return 1;
84  }
85  auto issues = validateMap(config.mapFile, config.validationConfig);
86  printAllIssues(issues);
87  return int(!issues.empty());
88 }
89 
90 } // namespace validation
91 } // namespace lanelet
lanelet::validation::CommandLineConfig::help
bool help
Definition: Cli.h:10
lanelet::validation::buildReport
IssueReport buildReport(std::vector< DetectedIssues > issues)
Generates the issue report.
Definition: Validation.cpp:104
lanelet
lanelet::validation::ValidationConfig::checksFilter
std::string checksFilter
Definition: Validation.h:24
Cli.h
lanelet::validation::CommandLineConfig::mapFile
std::string mapFile
Definition: Cli.h:8
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::validateMap
std::vector< DetectedIssues > validateMap(LaneletMap &map, const ValidationConfig &config)
Definition: Validation.cpp:120
lanelet::validation::runFromConfig
int runFromConfig(const CommandLineConfig &config)
Runs the configuration and returns the programs's return value (0 on success, 1 if issues found)
Definition: Cli.cpp:66
lanelet::validation::CommandLineConfig
Definition: Cli.h:6
lanelet::validation::parseCommandLine
CommandLineConfig parseCommandLine(int argc, const char *argv[])
obtain the configuration from command line arguments
Definition: Cli.cpp:11
lanelet::validation::CommandLineConfig::validationConfig
ValidationConfig validationConfig
Definition: Cli.h:7
lanelet::validation::printAllIssues
void printAllIssues(const std::vector< DetectedIssues > &issues)
prints a vector of issues to the command line
Definition: Cli.cpp:55
lanelet::validation::CommandLineConfig::print
bool print
Definition: Cli.h:9


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