diff --git a/map/autoware_lanelet2_map_validator/src/lib/cli.cpp b/map/autoware_lanelet2_map_validator/src/lib/cli.cpp index a3fff571..00bf7cc9 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/cli.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/cli.cpp @@ -30,28 +30,45 @@ MetaConfig parseCommandLine(int argc, const char * argv[]) po::options_description desc( "Runs a set of validators on a map. Think of it like a linter. The following checks are " "available"); - desc.add_options()("help,h", "This help message")( - "map_file,m", po::value(), "Path to the map to be validated")( + + // clang-format off + desc.add_options() + ( + "help,h", "This help message" + )( + "map_file,m", po::value(), "Path to the map to be validated" + )( "input_requirements,i", po::value(), - "Path to the yaml file where the list of requirements and validators is written")( + "Path to the yaml file where the list of requirements and validators is written" + )( "output_directory,o", po::value(), - "Directory to save the list of validation results in a yaml format")( + "Directory to save the list of validation results in a yaml format" + )( "validator,v", po::value(&validation_config.checksFilter), "Comma separated list of regexes to filter the applicable validators. Will run all " - "validators by default. Example: routing_graph.* to run all checks for the routing graph")( + "validators by default. Example: routing_graph.* to run all checks for the routing graph" + )( "projector,p", po::value(&config.projector_type)->composing(), "Projector used for loading lanelet map. Available projectors are: mgrs, utm, " - "transverse_mercator. (default: mgrs)")( + "transverse_mercator. (default: mgrs)" + )( "location,l", po::value(&validation_config.location)->default_value(validation_config.location), - "Location of the map (for instantiating the traffic rules), e.g. de for Germany")( + "Location of the map (for instantiating the traffic rules), e.g. de for Germany" + )( "participants", po::value(&validation_config.participants)->composing(), - "Participants for which the routing graph will be instantiated (default: vehicle)")( + "Participants for which the routing graph will be instantiated (default: vehicle)" + )( "lat", po::value(&validation_config.origin.lat)->default_value(validation_config.origin.lat), "Latitude coordinate of map origin. This is required for the transverse mercator " - "and utm projector.")( + "and utm projector." + )( "lon", po::value(&validation_config.origin.lon)->default_value(validation_config.origin.lon), "Longitude coordinate of map origin. This is required for the transverse mercator " - "and utm projector.")("print", "Print all available checker without running them"); + "and utm projector." + )( + "print", "Print all available checker without running them" + ); + // clang-format on po::variables_map vm; po::positional_options_description pos; diff --git a/map/autoware_lanelet2_map_validator/src/lib/validation.cpp b/map/autoware_lanelet2_map_validator/src/lib/validation.cpp index 161cfc36..9a8d0cae 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validation.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/validation.cpp @@ -48,23 +48,6 @@ std::vector validateMap(const MetaConfig & const auto & cm_config = config.command_line_config; const auto & val_config = config.command_line_config.validationConfig; - const auto & parse_filter = [](const std::string & str) { - std::vector regexes; - std::stringstream ss(str); - - while (ss.good()) { - std::string substr; - getline(ss, substr, ','); - if (substr.empty()) { - continue; - } - regexes.emplace_back(substr, std::regex::basic | std::regex::icase); - } - return regexes; - }; - - auto checks = parse_filter(val_config.checksFilter); - std::vector issues; lanelet::LaneletMapPtr map; lanelet::validation::Strings errors;