From 1d9f97e1fe7270c7fcca49fa0c64eb693e9036c6 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Fri, 13 Sep 2024 09:55:21 +0900 Subject: [PATCH 01/45] introduce autoware_lanelet2_map_validator to autoware_tools Signed-off-by: TaikiYamada4 --- .../CMakeLists.txt | 40 ++ map/autoware_lanelet2_map_validator/README.md | 3 + .../autoware_lanelet2_map_validator/cli.hpp | 43 +++ .../autoware_lanelet2_map_validator/utils.hpp | 85 +++++ .../validation.hpp | 52 +++ .../vals/missing_regulatory_elements.hpp | 54 +++ .../vals/regulatory_element_details.hpp | 50 +++ .../package.xml | 28 ++ .../src/lib/cli.cpp | 95 +++++ .../src/lib/validation.cpp | 91 +++++ .../lib/vals/missing_regulatory_elements.cpp | 231 ++++++++++++ .../lib/vals/regulatory_element_details.cpp | 183 ++++++++++ .../src/main.cpp | 54 +++ .../src/test_missing_regulatory_elements.cpp | 215 +++++++++++ .../src/test_regulatory_element_details.cpp | 343 ++++++++++++++++++ 15 files changed, 1567 insertions(+) create mode 100644 map/autoware_lanelet2_map_validator/CMakeLists.txt create mode 100644 map/autoware_lanelet2_map_validator/README.md create mode 100644 map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/cli.hpp create mode 100644 map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/utils.hpp create mode 100644 map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validation.hpp create mode 100644 map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/vals/missing_regulatory_elements.hpp create mode 100644 map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/vals/regulatory_element_details.hpp create mode 100644 map/autoware_lanelet2_map_validator/package.xml create mode 100644 map/autoware_lanelet2_map_validator/src/lib/cli.cpp create mode 100644 map/autoware_lanelet2_map_validator/src/lib/validation.cpp create mode 100644 map/autoware_lanelet2_map_validator/src/lib/vals/missing_regulatory_elements.cpp create mode 100644 map/autoware_lanelet2_map_validator/src/lib/vals/regulatory_element_details.cpp create mode 100644 map/autoware_lanelet2_map_validator/src/main.cpp create mode 100644 map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp create mode 100644 map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp diff --git a/map/autoware_lanelet2_map_validator/CMakeLists.txt b/map/autoware_lanelet2_map_validator/CMakeLists.txt new file mode 100644 index 00000000..422dfeb8 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/CMakeLists.txt @@ -0,0 +1,40 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_lanelet2_map_validator) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_find_build_dependencies() + +include_directories( + include +) + +file(GLOB_RECURSE autoware_lanelet2_map_validator_lib_src src/lib/*.cpp) +ament_auto_add_library(autoware_lanelet2_map_validator_lib SHARED + ${autoware_lanelet2_map_validator_lib_src} +) + +ament_auto_add_executable(autoware_lanelet2_map_validator src/main.cpp) +add_dependencies(autoware_lanelet2_map_validator autoware_lanelet2_map_validator_lib) +target_link_libraries(autoware_lanelet2_map_validator + autoware_lanelet2_map_validator_lib +) + +if(BUILD_TESTING) + function(add_validation_test VALIDATION_NAME) + ament_add_ros_isolated_gtest( + ${VALIDATION_NAME}_test + test/src/test_${VALIDATION_NAME}.cpp + ) + target_link_libraries( + ${VALIDATION_NAME}_test + autoware_lanelet2_map_validator_lib + ) + endfunction() + + add_validation_test(missing_regulatory_elements) + add_validation_test(regulatory_element_details) +endif() + +ament_auto_package() diff --git a/map/autoware_lanelet2_map_validator/README.md b/map/autoware_lanelet2_map_validator/README.md new file mode 100644 index 00000000..3fca533a --- /dev/null +++ b/map/autoware_lanelet2_map_validator/README.md @@ -0,0 +1,3 @@ +# autoware_lanelet2_map_validator + +This diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/cli.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/cli.hpp new file mode 100644 index 00000000..1260c672 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/cli.hpp @@ -0,0 +1,43 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__CLI_HPP_ +#define AUTOWARE_LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__CLI_HPP_ + +#include + +#include + +#include +#include + +namespace lanelet +{ +namespace autoware +{ +namespace validation +{ +struct MetaConfig +{ + lanelet::validation::CommandLineConfig command_line_config; + std::string projector_type; +}; + +MetaConfig parseCommandLine(int argc, const char * argv[]); + +} // namespace validation +} // namespace autoware +} // namespace lanelet + +#endif // AUTOWARE_LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__CLI_HPP_ diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/utils.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/utils.hpp new file mode 100644 index 00000000..dbf73948 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/utils.hpp @@ -0,0 +1,85 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__UTILS_HPP_ +#define AUTOWARE_LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__UTILS_HPP_ + +#include +#include + +#include +#include + +namespace lanelet +{ +namespace autoware +{ +namespace validation +{ +template +void appendIssues(std::vector & to, std::vector && from) +{ + to.insert(to.end(), std::make_move_iterator(from.begin()), std::make_move_iterator(from.end())); +} + +template +void checkPrimitivesType( + std::vector & in_vec, const std::string & expected_type, + const lanelet::validation::Issue & issue, lanelet::validation::Issues & issues) +{ + for (auto iter = in_vec.begin(); iter != in_vec.end(); ++iter) { + const auto & item = *iter; + const auto & attrs = item.attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Type); + if (it == attrs.end() || it->second != expected_type) { + issues.emplace_back(issue.severity, issue.primitive, item.id(), issue.message); + const auto new_it = in_vec.erase(iter); + if (new_it != in_vec.end()) { + iter = new_it; + } else { + break; + } + } + } +} + +template +void checkPrimitivesType( + std::vector & in_vec, const std::string & expected_type, const std::string & expected_subtype, + const lanelet::validation::Issue & issue, lanelet::validation::Issues & issues) +{ + for (auto iter = in_vec.begin(); iter != in_vec.end(); ++iter) { + const auto & item = *iter; + const auto & attrs = item.attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Type); + const auto & it_sub = attrs.find(lanelet::AttributeName::Subtype); + if ( + it == attrs.end() || it->second != expected_type || it_sub == attrs.end() || + it_sub->second != expected_subtype) { + issues.emplace_back(issue.severity, issue.primitive, item.id(), issue.message); + const auto new_it = in_vec.erase(iter); + if (new_it != in_vec.end()) { + iter = new_it; + } else { + break; + } + } + } +} + +} // namespace validation +} // namespace autoware +} // namespace lanelet + +#endif // AUTOWARE_LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__UTILS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validation.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validation.hpp new file mode 100644 index 00000000..42e71ea1 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validation.hpp @@ -0,0 +1,52 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__VALIDATION_HPP_ +#define AUTOWARE_LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__VALIDATION_HPP_ + +#include "autoware_lanelet2_map_validator/cli.hpp" +#include "autoware_lanelet2_map_validator/utils.hpp" + +#include +#include +#include +#include + +#include +#include +#include + +namespace +{ +namespace projector_names +{ +constexpr const char * mgrs = "mgrs"; +constexpr const char * transverse_mercator = "transverse_mercator"; +constexpr const char * utm = "utm"; +} // namespace projector_names +} // namespace + +namespace lanelet +{ +namespace autoware +{ +namespace validation +{ +std::unique_ptr getProjector(const MetaConfig & config); +std::vector validateMap(const MetaConfig & config); +} // namespace validation +} // namespace autoware +} // namespace lanelet + +#endif // AUTOWARE_LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__VALIDATION_HPP_ diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/vals/missing_regulatory_elements.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/vals/missing_regulatory_elements.hpp new file mode 100644 index 00000000..a0b9dcfa --- /dev/null +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/vals/missing_regulatory_elements.hpp @@ -0,0 +1,54 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__VALS__MISSING_REGULATORY_ELEMENTS_HPP_ +#define AUTOWARE_LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__VALS__MISSING_REGULATORY_ELEMENTS_HPP_ + +#include "autoware_lanelet2_map_validator/utils.hpp" +#include + +#include +#include +#include + +#include +#include + +#include + +namespace lanelet +{ +namespace validation +{ + +class MissingRegulatoryElementsChecker : public lanelet::validation::MapValidator +{ +public: + constexpr static const char * name() { return "mapping.missing_regulatory_elements"; } + + lanelet::validation::Issues operator()(const lanelet::LaneletMap & map) override; + +private: + lanelet::validation::Issues checkMissingReglatoryElementsInTrafficLight( + const lanelet::LaneletMap & map); + lanelet::validation::Issues checkMissingReglatoryElementsInCrosswalk( + const lanelet::LaneletMap & map); + lanelet::validation::Issues checkMissingReglatoryElementsInStopLine( + const lanelet::LaneletMap & map); + std::set tl_elem_with_cw_; +}; +} // namespace validation +} // namespace lanelet + +#endif // AUTOWARE_LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__VALS__MISSING_REGULATORY_ELEMENTS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/vals/regulatory_element_details.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/vals/regulatory_element_details.hpp new file mode 100644 index 00000000..f142628d --- /dev/null +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/vals/regulatory_element_details.hpp @@ -0,0 +1,50 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_lanelet2_map_validator/utils.hpp" +#include +#include + +#include + +#include +#include + +#include +#include + +namespace lanelet +{ +namespace validation +{ + +#ifndef LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__VALS__REGULATORY_ELEMENT_DETAILS_HPP_ +#define LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__VALS__REGULATORY_ELEMENT_DETAILS_HPP_ + +class RegulatoryElementDetailsChecker : public lanelet::validation::MapValidator +{ +public: + constexpr static const char * name() { return "mapping.regulatory_elements_details"; } + + lanelet::validation::Issues operator()(const lanelet::LaneletMap & map) override; + +private: + bool isPedestrianTrafficLight(const std::vector & traffic_lights); + lanelet::validation::Issues checkRegulatoryElementOfTrafficLight(const lanelet::LaneletMap & map); + lanelet::validation::Issues checkRegulatoryElementOfCrosswalk(const lanelet::LaneletMap & map); +}; +} // namespace validation +} // namespace lanelet + +#endif // LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__VALS__REGULATORY_ELEMENT_DETAILS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/package.xml b/map/autoware_lanelet2_map_validator/package.xml new file mode 100644 index 00000000..7ffc93d2 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/package.xml @@ -0,0 +1,28 @@ + + + + autoware_lanelet2_map_validator + 0.1.0 + Validation tool for lanelet2 maps especially for Autoware usage + Taiki Yamada + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + autoware_lanelet2_extension + lanelet2_core + lanelet2_io + lanelet2_maps + lanelet2_projection + lanelet2_routing + lanelet2_traffic_rules + lanelet2_validation + rclcpp + + ament_cmake_ros + + + ament_cmake + + diff --git a/map/autoware_lanelet2_map_validator/src/lib/cli.cpp b/map/autoware_lanelet2_map_validator/src/lib/cli.cpp new file mode 100644 index 00000000..11f8c4d6 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/lib/cli.cpp @@ -0,0 +1,95 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_lanelet2_map_validator/cli.hpp" + +namespace po = boost::program_options; + +namespace lanelet +{ +namespace autoware +{ +namespace validation +{ + +MetaConfig parseCommandLine(int argc, const char * argv[]) +{ + MetaConfig config; + auto & validation_config = config.command_line_config.validationConfig; + 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") + + ("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") + + ("projector,p", po::value(&config.projector_type)->composing(), + "Projector used for loading lanelet map. Available projectors are: mgrs, utm, " + "transverse_mercator. (default: mgrs)") + + ("location,l", + po::value(&validation_config.location)->default_value(validation_config.location), + "Location of the map (for instanciating the traffic rules), e.g. de for Germany") + + ("participants", po::value(&validation_config.participants)->composing(), + "Participants for which the routing graph will be instanciated (default: vehicle)") + + ("lat", + po::value(&validation_config.origin.lat) + ->default_value(validation_config.origin.lat), + "latitude coordinate of map origin. This is reguired for the transverse mercator " + "and utm projector.") + + ("lon", + po::value(&validation_config.origin.lon) + ->default_value(validation_config.origin.lon), + "longitude coofdinate of map origin. This is reguired for the transverse mercator " + "and utm projector.") + + ("print", "Only print all avalible checker, but dont run them"); + po::variables_map vm; + po::positional_options_description pos; + pos.add("map_file", 1); + po::store(po::command_line_parser(argc, argv).options(desc).positional(pos).run(), vm); + po::notify(vm); + config.command_line_config.help = vm.count("help") != 0; + config.command_line_config.print = vm.count("print") != 0; + if (vm.count("map_file") != 0) { + config.command_line_config.mapFile = + vm["map_file"].as(); + } + if ( + (vm.count("lat") != 0 && vm.count("lon") != 0) && + (config.projector_type == "tm" || config.projector_type == "utm")) { + throw std::runtime_error( + "Please set latitude and longitude. These are required for " + config.projector_type + + " projector. Please refer to the help message."); + } + if (config.command_line_config.help) { + std::cout << '\n' << desc; + } else if (config.command_line_config.mapFile.empty() && !config.command_line_config.print) { + std::cout << "Please pass either a valid file or '--print' or '--help'!\n"; + } + return config; +} + +} // namespace validation +} // namespace autoware +} // namespace lanelet diff --git a/map/autoware_lanelet2_map_validator/src/lib/validation.cpp b/map/autoware_lanelet2_map_validator/src/lib/validation.cpp new file mode 100644 index 00000000..15f03c23 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/lib/validation.cpp @@ -0,0 +1,91 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_lanelet2_map_validator/validation.hpp" +#include +#include + +namespace lanelet +{ +namespace autoware +{ +namespace validation +{ + +std::unique_ptr getProjector(const MetaConfig & config) +{ + const auto & val_config = config.command_line_config.validationConfig; + if (config.projector_type == projector_names::mgrs) { + return std::make_unique(); + } else if (config.projector_type == projector_names::transverse_mercator) { + return std::make_unique( + lanelet::Origin{val_config.origin}); + } else if (config.projector_type == projector_names::utm) { + return std::make_unique(lanelet::Origin{val_config.origin}); + } else { + std::cerr << "Set to default projector: MGRS projector" << std::endl; + return std::make_unique(); + } +} + +std::vector validateMap(const MetaConfig & config) +{ + 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; + try { + const auto & projector = getProjector(config); + map = lanelet::load(cm_config.mapFile, *projector, &errors); + if (!errors.empty()) { + std::cout << "!errors.empty()" << std::endl; + issues.emplace_back("general", utils::transform(errors, [](auto & error) { + return lanelet::validation::Issue( + lanelet::validation::Severity::Error, error); + })); + } + } catch (lanelet::LaneletError & err) { + std::cout << "catch" << std::endl; + issues.emplace_back("general", utils::transform(errors, [](auto & error) { + return lanelet::validation::Issue( + lanelet::validation::Severity::Error, error); + })); + } + + appendIssues(issues, lanelet::validation::validateMap(*map, val_config)); + return issues; +} + +} // namespace validation +} // namespace autoware +} // namespace lanelet diff --git a/map/autoware_lanelet2_map_validator/src/lib/vals/missing_regulatory_elements.cpp b/map/autoware_lanelet2_map_validator/src/lib/vals/missing_regulatory_elements.cpp new file mode 100644 index 00000000..13ba5602 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/lib/vals/missing_regulatory_elements.cpp @@ -0,0 +1,231 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +namespace lanelet +{ +namespace validation +{ +namespace +{ +lanelet::validation::RegisterMapValidator reg; +} // namespace + +lanelet::validation::Issues MissingRegulatoryElementsChecker::operator()( + const lanelet::LaneletMap & map) +{ + // All issues found by all validators + lanelet::validation::Issues issues; + + // Append issues found by each validator + lanelet::autoware::validation::appendIssues( + issues, checkMissingReglatoryElementsInTrafficLight(map)); + lanelet::autoware::validation::appendIssues( + issues, checkMissingReglatoryElementsInCrosswalk(map)); + lanelet::autoware::validation::appendIssues(issues, checkMissingReglatoryElementsInStopLine(map)); + return issues; +} + +lanelet::validation::Issues +MissingRegulatoryElementsChecker::checkMissingReglatoryElementsInTrafficLight( + const lanelet::LaneletMap & map) +{ + lanelet::validation::Issues issues; + + // Get all line strings whose type is traffic light + auto tl_ids = + map.lineStringLayer | ranges::views::filter([](auto && ls) { + const auto & attrs = ls.attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Type); + return it != attrs.end() && it->second == lanelet::AttributeValueString::TrafficLight; + }) | + ranges::views::transform([](auto && ls) { return ls.id(); }) | ranges::views::unique; + + + std::cout << "tl_ids" << std::endl; + std::cout << typeid(decltype(tl_ids)).name() << std::endl; + for (const auto & id : tl_ids) { + std::cout << id << std::endl; + } + + // Filter regulatory elements whose type is traffic light and has refers + auto reg_elem_tl = map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { + const auto & attrs = elem->attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + const auto & params = elem->getParameters(); + return it != attrs.end() && + it->second == lanelet::AttributeValueString::TrafficLight && + params.find(lanelet::RoleNameString::Refers) != params.end(); + }); + std::cout << "reg_elem_tl" << std::endl; + for (const auto & id : reg_elem_tl) { + std::cout << id << std::endl; + } + + // Get all line strings of traffic light referred by regulatory elements + std::set tl_ids_reg_elem; + for (const auto & elem : reg_elem_tl) { + const auto & refers = + elem->getParameters(lanelet::RoleName::Refers); + for (const auto & refer : refers) { + tl_ids_reg_elem.insert(refer.id()); + } + } + + std::cout << "tl_ids_reg_elem" << std::endl; + for (const auto & id : tl_ids_reg_elem) { + std::cout << id << std::endl; + } + + // Check if all line strings of traffic light referred by regulatory elements + for (const auto & tl_id : tl_ids) { + if (tl_ids_reg_elem.find(tl_id) == tl_ids_reg_elem.end()) { + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, tl_id, + "Traffic light must have a regulatory element."); + } + } + + return issues; +} + +lanelet::validation::Issues +MissingRegulatoryElementsChecker::checkMissingReglatoryElementsInCrosswalk( + const lanelet::LaneletMap & map) +{ + lanelet::validation::Issues issues; + + // Get all lanelets whose type is crosswalk + std::set cw_ids; + for (const auto & ll : map.laneletLayer) { + const auto & attrs = ll.attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + // Check if this lanelet is crosswalk + if (it != attrs.end() && it->second == lanelet::AttributeValueString::Crosswalk) { + cw_ids.insert(ll.id()); + + // Check if crosswalk has reg elem of traffic light + for (const auto & elem : ll.regulatoryElements()) { + const auto & attrs = elem->attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + if (it != attrs.end() && it->second == lanelet::AttributeValueString::TrafficLight) { + tl_elem_with_cw_.insert(elem->id()); + } + } + } + } + + std::cout << "cw_ids" << std::endl; + for (const auto & id : cw_ids) { + std::cout << id << std::endl; + } + + std::cout << "tl_elem_with_cw_" << std::endl; + for (const auto & id : tl_elem_with_cw_) { + std::cout << id << std::endl; + } + + // Filter regulatory elements whose type is crosswalk and has refers + auto reg_elem_cw = + map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { + const auto & attrs = elem->attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + return it != attrs.end();// && it->second == lanelet::AttributeValueString::Crosswalk; + });/* | + ranges::views::filter([](auto && elem) { + const auto & param = elem->getParameters(); + return param.find(lanelet::RoleNameString::Refers) != param.end(); + });*/ + + std::cout << "reg_elem_cw" << std::endl; + for (const auto & id : reg_elem_cw) { + std::cout << id << std::endl; + } + + // Get all lanelets of crosswalk referred by regulatory elements + std::set cw_ids_reg_elem; + for (const auto & elem : reg_elem_cw) { + const auto & refers = elem->getParameters(lanelet::RoleName::Refers); + for (const lanelet::ConstLanelet & refer : refers) { + cw_ids_reg_elem.insert(refer.id()); + } + } + + std::cout << "cw_ids_reg_elem" << std::endl; + for (const auto & id : cw_ids_reg_elem) { + std::cout << id << std::endl; + } + + // Check if all lanelets of crosswalk referred by regulatory elements + for (const auto & cw_id : cw_ids) { + if (cw_ids_reg_elem.find(cw_id) == cw_ids_reg_elem.end()) { + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::Lanelet, cw_id, + "Crosswalk must have a regulatory element."); + } + } + + return issues; +} + +lanelet::validation::Issues +MissingRegulatoryElementsChecker::checkMissingReglatoryElementsInStopLine( + const lanelet::LaneletMap & map) +{ + lanelet::validation::Issues issues; + + // Get all line strings whose type is stop line + auto sl_ids = map.lineStringLayer | ranges::views::filter([](auto && ls) { + const auto & attrs = ls.attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Type); + return it != attrs.end() && it->second == lanelet::AttributeValueString::StopLine; + }) | + ranges::views::transform([](auto && ls) { return ls.id(); }) | + ranges::views::unique; + + // Filter regulatory elements whose refline type is stop line + auto reg_elem_sl = map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { + const auto & params = elem->getParameters(); + return params.find(lanelet::RoleNameString::RefLine) != params.end(); + }); + + // Get all line strings of stop line referred by regulatory elements + std::set sl_ids_reg_elem; + for (const auto & elem : reg_elem_sl) { + const auto & ref_lines = + elem->getParameters(lanelet::RoleName::RefLine); + for (const auto & ref_line : ref_lines) { + const auto & attrs = ref_line.attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Type); + if (it != attrs.end() && it->second == lanelet::AttributeValueString::StopLine) { + sl_ids_reg_elem.insert(ref_line.id()); + } + } + } + + // Check if all line strings of stop line referred by regulatory elements + for (const auto & sl_id : sl_ids) { + if (sl_ids_reg_elem.find(sl_id) == sl_ids_reg_elem.end()) { + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, sl_id, + "Stop Line must have a regulatory element."); + } + } + + return issues; +} + +} // namespace validation +} // namespace lanelet diff --git a/map/autoware_lanelet2_map_validator/src/lib/vals/regulatory_element_details.cpp b/map/autoware_lanelet2_map_validator/src/lib/vals/regulatory_element_details.cpp new file mode 100644 index 00000000..af5ca168 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/lib/vals/regulatory_element_details.cpp @@ -0,0 +1,183 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_lanelet2_map_validator/vals/regulatory_element_details.hpp" + +namespace lanelet +{ +namespace validation +{ +namespace +{ +lanelet::validation::RegisterMapValidator reg; +} // namespace + +lanelet::validation::Issues RegulatoryElementDetailsChecker::operator()( + const lanelet::LaneletMap & map) +{ + // All issues found by all validators + lanelet::validation::Issues issues; + + // Append issues found by each validator + lanelet::autoware::validation::appendIssues(issues, checkRegulatoryElementOfTrafficLight(map)); + lanelet::autoware::validation::appendIssues(issues, checkRegulatoryElementOfCrosswalk(map)); + return issues; +} + +bool RegulatoryElementDetailsChecker::isPedestrianTrafficLight( + const std::vector & traffic_lights) +{ + for (const auto & tl : traffic_lights) { + const auto & attrs = tl.attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + if (it == attrs.end() || it->second != "red_green") { + return false; + } + } + return true; +} + +lanelet::validation::Issues RegulatoryElementDetailsChecker::checkRegulatoryElementOfTrafficLight( + const lanelet::LaneletMap & map) +{ + lanelet::validation::Issues issues; + // filter regulatory element whose Subtype is traffic light + auto elems = + map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { + const auto & attrs = elem->attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + return it != attrs.end() && it->second == lanelet::AttributeValueString::TrafficLight; + }); + + for (const auto & elem : elems) { + // Get line strings of traffic light referred by regulatory element + auto refers = elem->getParameters(lanelet::RoleName::Refers); + // Get stop line referred by regulatory element + auto ref_lines = elem->getParameters(lanelet::RoleName::RefLine); + const auto & issue_tl = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, + lanelet::utils::getId(), + "Refers of traffic light regulatory element must have type of traffic_light."); + lanelet::autoware::validation::checkPrimitivesType( + refers, lanelet::AttributeValueString::TrafficLight, issue_tl, issues); + + const auto & issue_sl = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, + lanelet::utils::getId(), + "Refline of traffic light regulatory element must have type of stop_line."); + lanelet::autoware::validation::checkPrimitivesType( + ref_lines, lanelet::AttributeValueString::StopLine, issue_sl, issues); + + if (refers.empty()) { + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), "Regulatory element of traffic light must have a traffic light(refers)."); + } + // TODO(sgk-000): Check correct behavior if regulatory element has two or more traffic light + // else if (refers.size() != 1) { + // issues.emplace_back( + // lanelet::validation::Severity::Error, + // lanelet::validation::Primitive::RegulatoryElement, elem->id(), "Regulatory element of + // traffic light must have only one traffic light(refers)."); + // } + + // Report error if regulatory element does not have stop line and this is not a pedestrian + // traffic light + if (ref_lines.empty() && !isPedestrianTrafficLight(refers)) { + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), "Regulatory element of traffic light must have a stop line(ref_line)."); + } + } + return issues; +} + +lanelet::validation::Issues RegulatoryElementDetailsChecker::checkRegulatoryElementOfCrosswalk( + const lanelet::LaneletMap & map) +{ + lanelet::validation::Issues issues; + // filter elem whose Subtype is crosswalk + auto elems = map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { + const auto & attrs = elem->attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + return it != attrs.end() && it->second == lanelet::AttributeValueString::Crosswalk; + }); + + for (const auto & elem : elems) { + // Get lanelet of crosswalk referred by regulatory element + auto refers = elem->getParameters(lanelet::RoleName::Refers); + // Get stop line referred by regulatory element + auto ref_lines = elem->getParameters(lanelet::RoleName::RefLine); + // Get crosswalk polygon referred by regulatory element + auto crosswalk_polygons = elem->getParameters( + lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon); + + const auto & issue_cw = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::Lanelet, + lanelet::utils::getId(), + "Refers of crosswalk regulatory element must have type of crosswalk."); + lanelet::autoware::validation::checkPrimitivesType( + refers, lanelet::AttributeValueString::Lanelet, lanelet::AttributeValueString::Crosswalk, + issue_cw, issues); + + const auto & issue_sl = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, + lanelet::utils::getId(), + "Refline of crosswalk regulatory element must have type of stopline."); + lanelet::autoware::validation::checkPrimitivesType( + ref_lines, lanelet::AttributeValueString::StopLine, issue_sl, issues); + + const auto & issue_poly = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::Polygon, + lanelet::utils::getId(), + "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon."); + lanelet::autoware::validation::checkPrimitivesType( + crosswalk_polygons, lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon, + issue_poly, issues); + + // Report warning if regulatory element does not have crosswalk polygon + if (crosswalk_polygons.empty()) { + issues.emplace_back( + lanelet::validation::Severity::Warning, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), "Regulatory element of cross walk is nice to have crosswalk_polygon."); + } else if (crosswalk_polygons.size() > 1) { // Report error if regulatory element has two or + // more crosswalk polygon + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), "Regulatory element of cross walk must have only one crosswalk_polygon."); + } + // Report Info if regulatory element does not have stop line + if (ref_lines.empty()) { + issues.emplace_back( + lanelet::validation::Severity::Info, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), "Regulatory element of cross walk does not have stop line(ref_line)."); + } + // Report error if regulatory element does not have lanelet of crosswalk + if (refers.empty()) { + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), "Regulatory element of cross walk must have lanelet of crosswalk(refers)."); + } else if (refers.size() > 1) { // Report error if regulatory element has two or more lanelet + // of crosswalk + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), + "Regulatory element of cross walk must have only one lanelet of crosswalk(refers)."); + } + } + return issues; +} + +} // namespace validation +} // namespace lanelet diff --git a/map/autoware_lanelet2_map_validator/src/main.cpp b/map/autoware_lanelet2_map_validator/src/main.cpp new file mode 100644 index 00000000..2d9cb009 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/main.cpp @@ -0,0 +1,54 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_lanelet2_map_validator/validation.hpp" +#include "lanelet2_validation/Validation.h" + +#include + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + auto node = rclcpp::Node::make_shared("autoware_lanelet2_map_validator"); + + auto config = lanelet::autoware::validation::parseCommandLine( + argc, const_cast(argv)); // NOLINT + + auto command_line_config = config.command_line_config; + if (command_line_config.help) { + return 0; + } + if (command_line_config.print) { + auto checks = + lanelet::validation::availabeChecks(command_line_config.validationConfig.checksFilter); + if (checks.empty()) { + std::cout << "No checks found matching '" << command_line_config.validationConfig.checksFilter + << "'\n"; + } else { + std::cout << "Will use following checks:\n"; + for (auto & check : checks) { + std::cout << check << '\n'; + } + } + return 0; + } + if (command_line_config.mapFile.empty()) { + std::cout << "No map file specified" << std::endl; + return 1; + } + + auto issues = lanelet::autoware::validation::validateMap(config); + lanelet::validation::printAllIssues(issues); + return static_cast(!issues.empty()); +} diff --git a/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp new file mode 100644 index 00000000..a5a1da18 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp @@ -0,0 +1,215 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_lanelet2_map_validator/vals/missing_regulatory_elements.hpp" + +#include + +using lanelet::AttributeMap; +using lanelet::AttributeName; +using lanelet::AttributeValueString; +using lanelet::Lanelet; +using lanelet::LaneletMapPtr; +using lanelet::LineString3d; +using lanelet::Point3d; +using lanelet::Polygon3d; +using lanelet::RegulatoryElementPtr; +using lanelet::TrafficLight; +using lanelet::autoware::Crosswalk; +using lanelet::utils::getId; +class TestSuite : public ::testing::Test +{ +public: + TestSuite() { initializeAttributes(); } + + ~TestSuite() override = default; + + void initializeAttributes() + { + // Stop Line + sl_attr_[AttributeName::Type] = AttributeValueString::StopLine; + + // Traffic Light + tl_attr_[AttributeName::Type] = AttributeValueString::TrafficLight; + tl_attr_[AttributeName::Subtype] = "red_yellow_green"; + tl_attr_["height"] = "0.5"; + + // Crosswalk polygon + cw_poly_attr_[AttributeName::Type] = + lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon; + + // Crosswalk + cw_attr_[AttributeName::Type] = AttributeValueString::Lanelet; + cw_attr_[AttributeName::Subtype] = AttributeValueString::Crosswalk; + cw_attr_[AttributeName::SpeedLimit] = "10"; + cw_attr_[AttributeName::OneWay] = "no"; + cw_attr_[AttributeName::Location] = AttributeValueString::Urban; + cw_attr_[AttributeName::ParticipantPedestrian] = "yes"; + + // Regulatory element of traffic light + AttributeMap tl_re_attr_ = AttributeMap(); + tl_re_attr_[AttributeName::Type] = AttributeValueString::RegulatoryElement; + tl_re_attr_[AttributeName::Subtype] = AttributeValueString::TrafficLight; + + // Regulatory element of crosswalk + AttributeMap cw_re_attr_ = AttributeMap(); + cw_re_attr_[AttributeName::Type] = AttributeValueString::RegulatoryElement; + cw_re_attr_[AttributeName::Subtype] = AttributeValueString::Crosswalk; + } + + void addTestMap(LaneletMapPtr in_map_ptr) + { + // Create test map + + // Points for stop line + Point3d p0 = Point3d(getId(), 0.0, 0.0, 0.1); + Point3d p1 = Point3d(getId(), 0.0, 1.0, 0.1); + Point3d p2 = Point3d(getId(), 0.0, 2.0, 0.1); + // Points for traffic light + Point3d p3 = Point3d(getId(), 0.0, 0.0, 5.0); + Point3d p4 = Point3d(getId(), 0.0, 1.0, 5.0); + Point3d p5 = Point3d(getId(), 0.0, 2.0, 5.0); + // Points for crosswalk + Point3d p6 = Point3d(getId(), 1.0, 0.0, 0.1); + Point3d p7 = Point3d(getId(), 1.0, 1.0, 0.1); + Point3d p8 = Point3d(getId(), 1.0, 2.0, 0.1); + Point3d p9 = Point3d(getId(), 2.0, 0.0, 0.1); + Point3d p10 = Point3d(getId(), 2.0, 1.0, 0.1); + Point3d p11 = Point3d(getId(), 2.0, 2.0, 0.1); + + // Stop line + LineString3d sl1 = LineString3d(getId(), {p0, p1}, sl_attr_); + LineString3d sl2 = LineString3d(getId(), {p1, p2}, sl_attr_); + + LineString3d tl1 = LineString3d(getId(), {p3, p4}, tl_attr_); + LineString3d tl2 = LineString3d(getId(), {p4, p5}, tl_attr_); + + // LineStrings for crosswalk + LineString3d cw_ls1 = LineString3d(getId(), {p6, p7}); + LineString3d cw_ls2 = LineString3d(getId(), {p7, p8}); + LineString3d cw_ls3 = LineString3d(getId(), {p9, p10}); + LineString3d cw_ls4 = LineString3d(getId(), {p10, p11}); + + Polygon3d cw_poly1 = Polygon3d(getId(), {p7, p6, p9, p10, p7}, cw_poly_attr_); + Polygon3d cw_poly2 = Polygon3d(getId(), {p8, p7, p10, p11, p8}, cw_poly_attr_); + // Lanelets for crosswalk + Lanelet cw1 = Lanelet(getId(), cw_ls1, cw_ls3, cw_attr_); + Lanelet cw2 = Lanelet(getId(), cw_ls2, cw_ls4, cw_attr_); + + // Traffic light regulatory element + RegulatoryElementPtr tl_reg_elem1, tl_reg_elem2; + tl_reg_elem1 = TrafficLight::make(getId(), tl_re_attr_, {tl1}, {sl1}); + tl_reg_elem2 = TrafficLight::make(getId(), tl_re_attr_, {tl2}, {sl2}); + + // Crosswalk regulatory element + RegulatoryElementPtr cw_reg_elem1, cw_reg_elem2; + cw_reg_elem1 = Crosswalk::make(getId(), cw_re_attr_, cw1, cw_poly1, {sl1}); + cw_reg_elem2 = Crosswalk::make(getId(), cw_re_attr_, cw2, cw_poly2, {sl2}); + + cw1.addRegulatoryElement(cw_reg_elem1); + cw2.addRegulatoryElement(cw_reg_elem2); + + // Add elements to map + for (const auto & re : {tl_reg_elem1, tl_reg_elem2}) { + in_map_ptr->add(re); + } + for (const auto & cw : {cw1, cw2}) { + in_map_ptr->add(cw); + } + } + AttributeMap sl_attr_, tl_attr_, cw_attr_, cw_poly_attr_, tl_re_attr_, cw_re_attr_; + lanelet::validation::MissingRegulatoryElementsChecker checker_; + +private: +}; + +TEST_F(TestSuite, ValidatorAvailability) // NOLINT for gtest +{ + lanelet::validation::Strings validators = lanelet::validation::availabeChecks( + lanelet::validation::MissingRegulatoryElementsChecker::name()); + uint8_t expected_num_validators = 1; + EXPECT_EQ(expected_num_validators, validators.size()); + for (const auto & v : validators) { + EXPECT_EQ(lanelet::validation::MissingRegulatoryElementsChecker::name(), v); + } +} + +TEST_F(TestSuite, MissingRegulatoryElementOfTrafficLight) // NOLINT for gtest +{ + // Check missing regulatory element of traffic light + + const auto & tl_no_reg_elem = LineString3d( + 99999, {Point3d(getId(), 0.0, 3.0, 5.0), Point3d(getId(), 0.0, 4.0, 5.0)}, tl_attr_); + LaneletMapPtr test_map_ptr = lanelet::utils::createMap({tl_no_reg_elem}); + addTestMap(test_map_ptr); + + const auto & issues = checker_(*test_map_ptr); + + uint8_t expected_num_issues = 1; + static constexpr const char * expected_message = "Traffic light must have a regulatory element."; + EXPECT_EQ(expected_num_issues, issues.size()); + for (const auto & issue : issues) { + EXPECT_EQ(99999, issue.id); + EXPECT_EQ(expected_message, issue.message); + EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); + EXPECT_EQ(lanelet::validation::Primitive::LineString, issue.primitive); + } +} + +TEST_F(TestSuite, MissingRegulatoryElementOfCrosswalk) // NOLINT for gtest +{ + // Check missing regulatory element of crosswalk + + const auto & cw_no_reg_elem = Lanelet( + 99999, + LineString3d(getId(), {Point3d(getId(), 3.0, 0.0, 0.1), Point3d(getId(), 3.0, 1.0, 0.1)}), + LineString3d(getId(), {Point3d(getId(), 3.0, 1.0, 0.1), Point3d(getId(), 3.0, 2.0, 0.1)}), + cw_attr_); + LaneletMapPtr test_map_ptr = lanelet::utils::createMap({cw_no_reg_elem}); + addTestMap(test_map_ptr); + + const auto & issues = checker_(*test_map_ptr); + + uint8_t expected_num_issues = 1; + static constexpr const char * expected_message = "Crosswalk must have a regulatory element."; + EXPECT_EQ(expected_num_issues, issues.size()); + for (const auto & issue : issues) { + EXPECT_EQ(99999, issue.id); + EXPECT_EQ(expected_message, issue.message); + EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); + EXPECT_EQ(lanelet::validation::Primitive::Lanelet, issue.primitive); + } +} + +TEST_F(TestSuite, MissingRegulatoryElementOfStopLine) // NOLINT for gtest +{ + // Check missing regulatory element of stop line + + const auto & sl_no_reg_elem = LineString3d( + 99999, {Point3d(getId(), 0.0, 3.0, 5.0), Point3d(getId(), 0.0, 4.0, 5.0)}, sl_attr_); + LaneletMapPtr test_map_ptr = lanelet::utils::createMap({sl_no_reg_elem}); + addTestMap(test_map_ptr); + + const auto & issues = checker_(*test_map_ptr); + + uint8_t expected_num_issues = 1; + static constexpr const char * expected_message = "Stop Line must have a regulatory element."; + EXPECT_EQ(expected_num_issues, issues.size()); + for (const auto & issue : issues) { + EXPECT_EQ(99999, issue.id); + EXPECT_EQ(expected_message, issue.message); + EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); + EXPECT_EQ(lanelet::validation::Primitive::LineString, issue.primitive); + } +} diff --git a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp new file mode 100644 index 00000000..b9a98e25 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp @@ -0,0 +1,343 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_lanelet2_map_validator/vals/regulatory_element_details.hpp" + +#include + +using lanelet::AttributeMap; +using lanelet::AttributeName; +using lanelet::AttributeValueString; +using lanelet::Lanelet; +using lanelet::LaneletMapPtr; +using lanelet::LineString3d; +using lanelet::Point3d; +using lanelet::Polygon3d; +using lanelet::RegulatoryElementPtr; +using lanelet::TrafficLight; +using lanelet::autoware::Crosswalk; +using lanelet::utils::getId; +class TestSuite : public ::testing::Test +{ +public: + TestSuite() { initializeAttributes(); } + + ~TestSuite() override = default; + + void initializeAttributes() + { + // Stop Line + sl_attr[AttributeName::Type] = AttributeValueString::StopLine; + + // Traffic Light + tl_attr[AttributeName::Type] = AttributeValueString::TrafficLight; + tl_attr[AttributeName::Subtype] = "red_yellow_green"; + tl_attr["height"] = "0.5"; + + // Crosswalk polygon + cw_poly_attr[AttributeName::Type] = + lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon; + + // Crosswalk + cw_attr[AttributeName::Type] = AttributeValueString::Lanelet; + cw_attr[AttributeName::Subtype] = AttributeValueString::Crosswalk; + cw_attr[AttributeName::SpeedLimit] = "10"; + cw_attr[AttributeName::OneWay] = "no"; + cw_attr[AttributeName::Location] = AttributeValueString::Urban; + cw_attr[AttributeName::ParticipantPedestrian] = "yes"; + + // Regulatory element of traffic light + AttributeMap tl_re_attr = AttributeMap(); + tl_re_attr[AttributeName::Type] = AttributeValueString::RegulatoryElement; + tl_re_attr[AttributeName::Subtype] = AttributeValueString::TrafficLight; + + // Regulatory element of crosswalk + AttributeMap cw_re_attr = AttributeMap(); + cw_re_attr[AttributeName::Type] = AttributeValueString::RegulatoryElement; + cw_re_attr[AttributeName::Subtype] = AttributeValueString::Crosswalk; + } + + void addTestMap(LaneletMapPtr in_map_ptr) + { + // Create test map + + // Points for stop line + Point3d p0 = Point3d(getId(), 0.0, 0.0, 0.1); + Point3d p1 = Point3d(getId(), 0.0, 1.0, 0.1); + Point3d p2 = Point3d(getId(), 0.0, 2.0, 0.1); + // Points for traffic light + Point3d p3 = Point3d(getId(), 0.0, 0.0, 5.0); + Point3d p4 = Point3d(getId(), 0.0, 1.0, 5.0); + Point3d p5 = Point3d(getId(), 0.0, 2.0, 5.0); + // Points for crosswalk + Point3d p6 = Point3d(getId(), 1.0, 0.0, 0.1); + Point3d p7 = Point3d(getId(), 1.0, 1.0, 0.1); + Point3d p8 = Point3d(getId(), 1.0, 2.0, 0.1); + Point3d p9 = Point3d(getId(), 2.0, 0.0, 0.1); + Point3d p10 = Point3d(getId(), 2.0, 1.0, 0.1); + Point3d p11 = Point3d(getId(), 2.0, 2.0, 0.1); + + // Stop line + LineString3d sl1 = LineString3d(getId(), {p0, p1}, sl_attr); + LineString3d sl2 = LineString3d(getId(), {p1, p2}, sl_attr); + + LineString3d tl1 = LineString3d(getId(), {p3, p4}, tl_attr); + LineString3d tl2 = LineString3d(getId(), {p4, p5}, tl_attr); + + // LineStrings for crosswalk + LineString3d cw_ls1 = LineString3d(getId(), {p6, p7}); + LineString3d cw_ls2 = LineString3d(getId(), {p7, p8}); + LineString3d cw_ls3 = LineString3d(getId(), {p9, p10}); + LineString3d cw_ls4 = LineString3d(getId(), {p10, p11}); + + Polygon3d cw_poly1 = Polygon3d(getId(), {p7, p6, p9, p10, p7}, cw_poly_attr); + Polygon3d cw_poly2 = Polygon3d(getId(), {p8, p7, p10, p11, p8}, cw_poly_attr); + // Lanelets for crosswalk + Lanelet cw1 = Lanelet(getId(), cw_ls1, cw_ls3, cw_attr); + Lanelet cw2 = Lanelet(getId(), cw_ls2, cw_ls4, cw_attr); + + // Traffic light regulatory element + RegulatoryElementPtr tl_reg_elem1, tl_reg_elem2; + tl_reg_elem1 = TrafficLight::make(getId(), tl_re_attr, {tl1}, {sl1}); + tl_reg_elem2 = TrafficLight::make(getId(), tl_re_attr, {tl2}, {sl2}); + + // Crosswalk regulatory element + RegulatoryElementPtr cw_reg_elem1, cw_reg_elem2; + cw_reg_elem1 = Crosswalk::make(getId(), cw_re_attr, cw1, cw_poly1, {sl1}); + cw_reg_elem2 = Crosswalk::make(getId(), cw_re_attr, cw2, cw_poly2, {sl2}); + + cw1.addRegulatoryElement(cw_reg_elem1); + cw2.addRegulatoryElement(cw_reg_elem2); + + // Add elements to map + for (const auto & re : {tl_reg_elem1, tl_reg_elem2}) { + in_map_ptr->add(re); + } + for (const auto & cw : {cw1, cw2}) { + in_map_ptr->add(cw); + } + } + AttributeMap sl_attr, tl_attr, cw_attr, cw_poly_attr, tl_re_attr, cw_re_attr; + lanelet::validation::RegulatoryElementDetailsChecker checker_; + +private: +}; + +TEST_F(TestSuite, ValidatorAvailability) // NOLINT for gtest +{ + lanelet::validation::Strings validators = lanelet::validation::availabeChecks( + lanelet::validation::RegulatoryElementDetailsChecker::name()); + uint8_t expected_num_validators = 1; + EXPECT_EQ(expected_num_validators, validators.size()); + for (const auto & v : validators) { + EXPECT_EQ(lanelet::validation::RegulatoryElementDetailsChecker::name(), v); + } +} + +TEST_F(TestSuite, RegulatoryElementofTrafficLightWithoutTrafficLight) // NOLINT for gtest +{ + // Check regulatory element of traffic light without traffic light + + RegulatoryElementPtr tl_reg_elem_no_tl; + // Line string without traffic light attribute + const auto & ls = LineString3d(99998, {}); + LaneletMapPtr test_map_ptr = lanelet::utils::createMap({ls}); + // Traffic light regulatory element without traffic light. It refers to the line string without + // traffic light attribute. + tl_reg_elem_no_tl = TrafficLight::make( + 99999, tl_re_attr, {ls}, + {LineString3d( + getId(), {Point3d(getId(), 3.0, 3.0, 0.1), Point3d(getId(), 3.0, 4.0, 0.1)}, sl_attr)}); + test_map_ptr->add(tl_reg_elem_no_tl); + addTestMap(test_map_ptr); + + const auto & issues = checker_(*test_map_ptr); + + uint8_t expected_num_issues = 2; + static constexpr const char * expected_message1 = + "Refers of traffic light regulatory element must have type of traffic_light."; + static constexpr const char * expected_message2 = + "Regulatory element of traffic light must have a traffic light(refers)."; + EXPECT_EQ(expected_num_issues, issues.size()); + for (const auto & issue : issues) { + if (issue.id == 99998) { + EXPECT_EQ(expected_message1, issue.message); + EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); + EXPECT_EQ(lanelet::validation::Primitive::LineString, issue.primitive); + } else if (issue.id == 99999) { + EXPECT_EQ(expected_message2, issue.message); + EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); + EXPECT_EQ(lanelet::validation::Primitive::RegulatoryElement, issue.primitive); + } else { + FAIL() << "Unexpected issue id: " << issue.id; + } + } +} + +TEST_F(TestSuite, RegulatoryElementofTrafficLightWithoutStopLine) // NOLINT for gtest +{ + // Check regulatory element of traffic light without stop line + + RegulatoryElementPtr tl_reg_elem_no_sl; + // Line string without stop line attribute + const auto & ls = LineString3d(99998, {}); + const auto & tl = LineString3d( + getId(), {Point3d(getId(), 0.0, 3.0, 5.0), Point3d(getId(), 0.0, 4.0, 5.0)}, tl_attr); + LaneletMapPtr test_map_ptr = lanelet::utils::createMap({tl}); + // Traffic light regulatory element without stop line. It refers to the line string without stop + // line attribute. + tl_reg_elem_no_sl = TrafficLight::make(99999, tl_re_attr, {tl}, {ls}); + test_map_ptr->add(tl_reg_elem_no_sl); + addTestMap(test_map_ptr); + + const auto & issues = checker_(*test_map_ptr); + + uint8_t expected_num_issues = 2; + static constexpr const char * expected_message1 = + "Refline of traffic light regulatory element must have type of stop_line."; + static constexpr const char * expected_message2 = + "Regulatory element of traffic light must have a stop line(ref_line)."; + EXPECT_EQ(expected_num_issues, issues.size()); + for (const auto & issue : issues) { + if (issue.id == 99998) { + EXPECT_EQ(expected_message1, issue.message); + EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); + EXPECT_EQ(lanelet::validation::Primitive::LineString, issue.primitive); + } else if (issue.id == 99999) { + EXPECT_EQ(expected_message2, issue.message); + EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); + EXPECT_EQ(lanelet::validation::Primitive::RegulatoryElement, issue.primitive); + } else { + FAIL() << "Unexpected issue id: " << issue.id; + } + } +} + +TEST_F(TestSuite, RegulatoryElementOfCrosswalkWithoutPolygon) // NOLINT for gtest +{ + // Check regulatory element of crosswalk without polygon + + RegulatoryElementPtr cw_reg_elem_no_poly; + Lanelet cw_no_poly = Lanelet( + getId(), + LineString3d(getId(), {Point3d(getId(), 3.0, 0.0, 0.1), Point3d(getId(), 3.0, 1.0, 0.1)}), + LineString3d(getId(), {Point3d(getId(), 3.0, 1.0, 0.1), Point3d(getId(), 3.0, 2.0, 0.1)}), + cw_attr); + + // Crosswalk regulatory element without cross walk polygon. It refers to the polygon without cross + // walk polygon attribute. + RegulatoryElementPtr reg_elem = Crosswalk::make( + 99999, cw_re_attr, cw_no_poly, Polygon3d(99998), + {LineString3d( + getId(), {Point3d(getId(), 3.0, 3.0, 0.1), Point3d(getId(), 3.0, 4.0, 0.1)}, sl_attr)}); + cw_no_poly.addRegulatoryElement(reg_elem); + LaneletMapPtr test_map_ptr = lanelet::utils::createMap({cw_no_poly}); + addTestMap(test_map_ptr); + + const auto & issues = checker_(*test_map_ptr); + + uint8_t expected_num_issues = 2; + static constexpr const char * expected_message1 = + "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon."; + static constexpr const char * expected_message2 = + "Regulatory element of cross walk is nice to have crosswalk_polygon."; + EXPECT_EQ(expected_num_issues, issues.size()); + for (const auto & issue : issues) { + if (issue.id == 99998) { + EXPECT_EQ(expected_message1, issue.message); + EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); + EXPECT_EQ(lanelet::validation::Primitive::Polygon, issue.primitive); + } else if (issue.id == 99999) { + EXPECT_EQ(expected_message2, issue.message); + EXPECT_EQ(lanelet::validation::Severity::Warning, issue.severity); + EXPECT_EQ(lanelet::validation::Primitive::RegulatoryElement, issue.primitive); + } else { + FAIL() << "Unexpected issue id: " << issue.id; + } + } +} + +TEST_F(TestSuite, RegulatoryElementOfCrosswalkWithoutStopline) // NOLINT for gtest +{ + // Check regulatory element of crosswalk without stop line + + Lanelet cw_no_sl = Lanelet( + getId(), + LineString3d(getId(), {Point3d(getId(), 3.0, 0.0, 0.1), Point3d(getId(), 3.0, 1.0, 0.1)}), + LineString3d(getId(), {Point3d(getId(), 3.0, 1.0, 0.1), Point3d(getId(), 3.0, 2.0, 0.1)}), + cw_attr); + + // Crosswalk regulatory element without stop line. + RegulatoryElementPtr reg_elem = Crosswalk::make( + 99999, cw_re_attr, cw_no_sl, + Polygon3d(getId(), {Point3d(getId(), 3.0, 3.0, 0.1)}, cw_poly_attr), {}); + cw_no_sl.addRegulatoryElement(reg_elem); + LaneletMapPtr test_map_ptr = lanelet::utils::createMap({cw_no_sl}); + addTestMap(test_map_ptr); + + const auto & issues = checker_(*test_map_ptr); + + uint8_t expected_num_issues = 1; + static constexpr const char * expected_message = + "Regulatory element of cross walk does not have stop line(ref_line)."; + EXPECT_EQ(expected_num_issues, issues.size()); + for (const auto & issue : issues) { + EXPECT_EQ(expected_message, issue.message); + EXPECT_EQ(99999, issue.id); + EXPECT_EQ(lanelet::validation::Severity::Info, issue.severity); + EXPECT_EQ(lanelet::validation::Primitive::RegulatoryElement, issue.primitive); + } +} + +TEST_F(TestSuite, RegulatoryElementOfCrosswalkWithoutCrosswalk) // NOLINT for gtest +{ + // Check regulatory element of crosswalk without crosswalk + + const auto poly = Polygon3d(getId(), {Point3d(getId(), 3.0, 3.0, 0.1)}, cw_poly_attr); + // Lanelet without crosswalk attribute + const auto ll = Lanelet( + 99998, + LineString3d(getId(), {Point3d(getId(), 3.0, 0.0, 0.1), Point3d(getId(), 3.0, 1.0, 0.1)}), + LineString3d(getId(), {Point3d(getId(), 3.0, 1.0, 0.1), Point3d(getId(), 3.0, 2.0, 0.1)})); + // Crosswalk regulatory element without crosswalk. It refers to the lanelet without crosswalk + RegulatoryElementPtr reg_elem = Crosswalk::make( + 99999, cw_re_attr, ll, poly, + {LineString3d( + getId(), {Point3d(getId(), 3.0, 3.0, 0.1), Point3d(getId(), 3.0, 4.0, 0.1)}, sl_attr)}); + LaneletMapPtr test_map_ptr = lanelet::utils::createMap({poly}); + addTestMap(test_map_ptr); + test_map_ptr->add(reg_elem); + + const auto & issues = checker_(*test_map_ptr); + + uint8_t expected_num_issues = 2; + static constexpr const char * expected_message1 = + "Refers of crosswalk regulatory element must have type of crosswalk."; + static constexpr const char * expected_message2 = + "Regulatory element of cross walk must have lanelet of crosswalk(refers)."; + EXPECT_EQ(expected_num_issues, issues.size()); + for (const auto & issue : issues) { + if (issue.id == 99998) { + EXPECT_EQ(expected_message1, issue.message); + EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); + EXPECT_EQ(lanelet::validation::Primitive::Lanelet, issue.primitive); + } else if (issue.id == 99999) { + EXPECT_EQ(expected_message2, issue.message); + EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); + EXPECT_EQ(lanelet::validation::Primitive::RegulatoryElement, issue.primitive); + } else { + FAIL() << "Unexpected issue id: " << issue.id; + } + } +} From 43d244165155c8d548d674675cf151c9c26eecf6 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Fri, 13 Sep 2024 10:57:54 +0900 Subject: [PATCH 02/45] wrote description a little to README.md Signed-off-by: TaikiYamada4 --- map/autoware_lanelet2_map_validator/README.md | 59 ++++++++++++++++++- 1 file changed, 58 insertions(+), 1 deletion(-) diff --git a/map/autoware_lanelet2_map_validator/README.md b/map/autoware_lanelet2_map_validator/README.md index 3fca533a..29d3d25e 100644 --- a/map/autoware_lanelet2_map_validator/README.md +++ b/map/autoware_lanelet2_map_validator/README.md @@ -1,3 +1,60 @@ # autoware_lanelet2_map_validator -This +`autoware_lanelet2_map_validator` is a tool to validate Lanelet2 maps to ensure that Autoware can work properly with it. + +The requirements for lanelet2 maps are described in [Vector Map creation requirement specifications (in Autoware Documentation)](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/map/map-requirements/vector-map-requirements-overview/). + +| ID | Requirements | +| -------- | ------------------------------------------------------- | +| vm-01-01 | Lanelet basics | +| vm-01-02 | Allowance for lane changes | +| vm-01-03 | Linestring sharing | +| vm-01-04 | Sharing of the centerline of lanes for opposing traffic | +| vm-01-05 | Lane geometry | +| vm-01-06 | Line position (1) | +| vm-01-07 | Line position (2) | +| vm-01-08 | Line position (3) | +| vm-01-09 | Speed limits | +| vm-01-10 | Centerline | +| vm-01-11 | Centerline connection (1) | +| vm-01-12 | Centerline connection (2) | +| vm-01-13 | Roads with no centerline (1) | +| vm-01-14 | Roads with no centerline (2) | +| vm-01-15 | Road shoulder | +| vm-01-16 | Road shoulder Linestring sharing | +| vm-01-17 | Side strip | +| vm-01-18 | Side strip Linestring sharing | +| vm-01-19 | Walkway | +| vm-02-01 | Stop line alignment | +| vm-02-02 | Stop sign | +| vm-03-01 | Intersection criteria | +| vm-03-02 | Lanelet's turn direction and virtual | +| vm-03-03 | Lanelet width in the intersection | +| vm-03-04 | Lanelet creation in the intersection | +| vm-03-05 | Lanelet division in the intersection | +| vm-03-06 | Guide lines in the intersection | +| vm-03-07 | Multiple lanelets in the intersection | +| vm-03-08 | Intersection Area range | +| vm-03-09 | Range of Lanelet in the intersection | +| vm-03-10 | Right of way (with signal) | +| vm-03-11 | Right of way (without signal) | +| vm-03-12 | Right of way supplements | +| vm-03-13 | Merging from private area, sidewalk | +| vm-03-14 | Road marking | +| vm-03-15 | Exclusive bicycle lane | +| vm-04-01 | Traffic light basics | +| vm-04-02 | Traffic light position and size | +| vm-04-03 | Traffic light lamps | +| vm-05-01 | Crosswalks across the road | +| vm-05-02 | Crosswalks with pedestrian signals | +| vm-05-03 | Deceleration for safety at crosswalks | +| vm-05-04 | Fences | +| vm-06-01 | Buffer Zone | +| vm-06-02 | No parking signs | +| vm-06-03 | No stopping signs | +| vm-06-04 | No stopping sections | +| vm-06-05 | Detection area | +| vm-07-01 | Vector Map creation range | +| vm-07-02 | Range of detecting pedestrians who enter the road | +| vm-07-03 | Guardrails, guard pipes, fences | +| vm-07-04 | Ellipsoidal height | From 0419b746b69c7eba8a4b7aff70bb20560304f154 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 13 Sep 2024 02:06:50 +0000 Subject: [PATCH 03/45] style(pre-commit): autofix --- .../include/autoware_lanelet2_map_validator/cli.hpp | 6 +++--- .../autoware_lanelet2_map_validator/utils.hpp | 6 +++--- .../autoware_lanelet2_map_validator/validation.hpp | 6 +++--- .../vals/missing_regulatory_elements.hpp | 8 ++++---- .../vals/regulatory_element_details.hpp | 8 ++++---- .../src/lib/validation.cpp | 1 + .../src/lib/vals/missing_regulatory_elements.cpp | 13 ++++++------- 7 files changed, 24 insertions(+), 24 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/cli.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/cli.hpp index 1260c672..f8aafee4 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/cli.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/cli.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__CLI_HPP_ -#define AUTOWARE_LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__CLI_HPP_ +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__CLI_HPP_ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__CLI_HPP_ #include @@ -40,4 +40,4 @@ MetaConfig parseCommandLine(int argc, const char * argv[]); } // namespace autoware } // namespace lanelet -#endif // AUTOWARE_LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__CLI_HPP_ +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__CLI_HPP_ diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/utils.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/utils.hpp index dbf73948..d5e851ed 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/utils.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/utils.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__UTILS_HPP_ -#define AUTOWARE_LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__UTILS_HPP_ +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__UTILS_HPP_ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__UTILS_HPP_ #include #include @@ -82,4 +82,4 @@ void checkPrimitivesType( } // namespace autoware } // namespace lanelet -#endif // AUTOWARE_LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__UTILS_HPP_ +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__UTILS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validation.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validation.hpp index 42e71ea1..9bd89649 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validation.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validation.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__VALIDATION_HPP_ -#define AUTOWARE_LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__VALIDATION_HPP_ +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATION_HPP_ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATION_HPP_ #include "autoware_lanelet2_map_validator/cli.hpp" #include "autoware_lanelet2_map_validator/utils.hpp" @@ -49,4 +49,4 @@ std::vector validateMap(const MetaConfig & } // namespace autoware } // namespace lanelet -#endif // AUTOWARE_LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__VALIDATION_HPP_ +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATION_HPP_ diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/vals/missing_regulatory_elements.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/vals/missing_regulatory_elements.hpp index a0b9dcfa..c47a848c 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/vals/missing_regulatory_elements.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/vals/missing_regulatory_elements.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__VALS__MISSING_REGULATORY_ELEMENTS_HPP_ -#define AUTOWARE_LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__VALS__MISSING_REGULATORY_ELEMENTS_HPP_ +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALS__MISSING_REGULATORY_ELEMENTS_HPP_ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALS__MISSING_REGULATORY_ELEMENTS_HPP_ #include "autoware_lanelet2_map_validator/utils.hpp" -#include +#include #include #include #include @@ -51,4 +51,4 @@ class MissingRegulatoryElementsChecker : public lanelet::validation::MapValidato } // namespace validation } // namespace lanelet -#endif // AUTOWARE_LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__VALS__MISSING_REGULATORY_ELEMENTS_HPP_ +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALS__MISSING_REGULATORY_ELEMENTS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/vals/regulatory_element_details.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/vals/regulatory_element_details.hpp index f142628d..0bce6919 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/vals/regulatory_element_details.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/vals/regulatory_element_details.hpp @@ -13,9 +13,9 @@ // limitations under the License. #include "autoware_lanelet2_map_validator/utils.hpp" + #include #include - #include #include @@ -29,8 +29,8 @@ namespace lanelet namespace validation { -#ifndef LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__VALS__REGULATORY_ELEMENT_DETAILS_HPP_ -#define LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__VALS__REGULATORY_ELEMENT_DETAILS_HPP_ +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALS__REGULATORY_ELEMENT_DETAILS_HPP_ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALS__REGULATORY_ELEMENT_DETAILS_HPP_ class RegulatoryElementDetailsChecker : public lanelet::validation::MapValidator { @@ -47,4 +47,4 @@ class RegulatoryElementDetailsChecker : public lanelet::validation::MapValidator } // namespace validation } // namespace lanelet -#endif // LANELET2_EXTENSION__AUTOWARE_LANELET2_VALIDATION__VALS__REGULATORY_ELEMENT_DETAILS_HPP_ +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALS__REGULATORY_ELEMENT_DETAILS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/lib/validation.cpp b/map/autoware_lanelet2_map_validator/src/lib/validation.cpp index 15f03c23..f09a447b 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validation.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/validation.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include "autoware_lanelet2_map_validator/validation.hpp" + #include #include diff --git a/map/autoware_lanelet2_map_validator/src/lib/vals/missing_regulatory_elements.cpp b/map/autoware_lanelet2_map_validator/src/lib/vals/missing_regulatory_elements.cpp index 13ba5602..3fadd7d8 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/vals/missing_regulatory_elements.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/vals/missing_regulatory_elements.cpp @@ -53,7 +53,6 @@ MissingRegulatoryElementsChecker::checkMissingReglatoryElementsInTrafficLight( }) | ranges::views::transform([](auto && ls) { return ls.id(); }) | ranges::views::unique; - std::cout << "tl_ids" << std::endl; std::cout << typeid(decltype(tl_ids)).name() << std::endl; for (const auto & id : tl_ids) { @@ -142,12 +141,12 @@ MissingRegulatoryElementsChecker::checkMissingReglatoryElementsInCrosswalk( map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { const auto & attrs = elem->attributes(); const auto & it = attrs.find(lanelet::AttributeName::Subtype); - return it != attrs.end();// && it->second == lanelet::AttributeValueString::Crosswalk; - });/* | - ranges::views::filter([](auto && elem) { - const auto & param = elem->getParameters(); - return param.find(lanelet::RoleNameString::Refers) != param.end(); - });*/ + return it != attrs.end(); // && it->second == lanelet::AttributeValueString::Crosswalk; + }); /* | + ranges::views::filter([](auto && elem) { + const auto & param = elem->getParameters(); + return param.find(lanelet::RoleNameString::Refers) != param.end(); + });*/ std::cout << "reg_elem_cw" << std::endl; for (const auto & id : reg_elem_cw) { From 37daad656ed40864f78742bfe9576321b9da6579 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Fri, 13 Sep 2024 17:57:00 +0900 Subject: [PATCH 04/45] Restore commented out parts. Removed rclcpp which is unused. Signed-off-by: TaikiYamada4 --- map/autoware_lanelet2_map_validator/package.xml | 1 - .../src/lib/vals/missing_regulatory_elements.cpp | 12 ++++++------ map/autoware_lanelet2_map_validator/src/main.cpp | 4 ---- 3 files changed, 6 insertions(+), 11 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/package.xml b/map/autoware_lanelet2_map_validator/package.xml index 7ffc93d2..5a657672 100644 --- a/map/autoware_lanelet2_map_validator/package.xml +++ b/map/autoware_lanelet2_map_validator/package.xml @@ -18,7 +18,6 @@ lanelet2_routing lanelet2_traffic_rules lanelet2_validation - rclcpp ament_cmake_ros diff --git a/map/autoware_lanelet2_map_validator/src/lib/vals/missing_regulatory_elements.cpp b/map/autoware_lanelet2_map_validator/src/lib/vals/missing_regulatory_elements.cpp index 3fadd7d8..d7a26054 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/vals/missing_regulatory_elements.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/vals/missing_regulatory_elements.cpp @@ -141,12 +141,12 @@ MissingRegulatoryElementsChecker::checkMissingReglatoryElementsInCrosswalk( map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { const auto & attrs = elem->attributes(); const auto & it = attrs.find(lanelet::AttributeName::Subtype); - return it != attrs.end(); // && it->second == lanelet::AttributeValueString::Crosswalk; - }); /* | - ranges::views::filter([](auto && elem) { - const auto & param = elem->getParameters(); - return param.find(lanelet::RoleNameString::Refers) != param.end(); - });*/ + return it != attrs.end() && it->second == lanelet::AttributeValueString::Crosswalk; + }) | + ranges::views::filter([](auto && elem) { + const auto & param = elem->getParameters(); + return param.find(lanelet::RoleNameString::Refers) != param.end(); + }); std::cout << "reg_elem_cw" << std::endl; for (const auto & id : reg_elem_cw) { diff --git a/map/autoware_lanelet2_map_validator/src/main.cpp b/map/autoware_lanelet2_map_validator/src/main.cpp index 2d9cb009..6c0534f4 100644 --- a/map/autoware_lanelet2_map_validator/src/main.cpp +++ b/map/autoware_lanelet2_map_validator/src/main.cpp @@ -15,12 +15,8 @@ #include "autoware_lanelet2_map_validator/validation.hpp" #include "lanelet2_validation/Validation.h" -#include - int main(int argc, char * argv[]) { - rclcpp::init(argc, argv); - auto node = rclcpp::Node::make_shared("autoware_lanelet2_map_validator"); auto config = lanelet::autoware::validation::parseCommandLine( argc, const_cast(argv)); // NOLINT From b6d8b36926a3b8a2b116822b9806889bca0eae76 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 13 Sep 2024 09:00:23 +0000 Subject: [PATCH 05/45] style(pre-commit): autofix --- map/autoware_lanelet2_map_validator/src/main.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/map/autoware_lanelet2_map_validator/src/main.cpp b/map/autoware_lanelet2_map_validator/src/main.cpp index 6c0534f4..b3d579b7 100644 --- a/map/autoware_lanelet2_map_validator/src/main.cpp +++ b/map/autoware_lanelet2_map_validator/src/main.cpp @@ -17,7 +17,6 @@ int main(int argc, char * argv[]) { - auto config = lanelet::autoware::validation::parseCommandLine( argc, const_cast(argv)); // NOLINT From 77416f289b0a3fb9bfbe2be46f89f9c1e32ee8b6 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Tue, 17 Sep 2024 18:26:59 +0900 Subject: [PATCH 06/45] Separate validation rules to samller pieces. Added validation template Signed-off-by: TaikiYamada4 --- .../autoware_lanelet2_map_validator/cli.hpp | 1 + ...ing_regulatory_elements_for_crosswalks.hpp | 41 ++++++ ...ulatory_element_details_for_crosswalks.hpp | 39 ++++++ .../missing_regulatory_elements.hpp | 4 +- .../regulatory_element_details.hpp | 4 +- ...ing_regulatory_elements_for_stop_lines.hpp | 40 ++++++ ...regulatory_elements_for_traffic_lights.hpp | 40 ++++++ ...ory_element_details_for_traffic_lights.hpp | 42 ++++++ .../validators/validator_template.hpp | 38 ++++++ ...sing_regulatory_elements_for_crosswalk.cpp | 124 ++++++++++++++++++ ...ulatory_element_details_for_crosswalks.cpp | 123 +++++++++++++++++ .../missing_regulatory_elements.cpp | 2 +- .../regulatory_element_details.cpp | 2 +- ...ing_regulatory_elements_for_stop_lines.cpp | 94 +++++++++++++ ..._regulatory_elements_for_traffic_light.cpp | 109 +++++++++++++++ ...ory_element_details_for_traffic_lights.cpp | 112 ++++++++++++++++ .../src/lib/validators/validator_template.cpp | 34 +++++ .../src/test_missing_regulatory_elements.cpp | 2 +- .../src/test_regulatory_element_details.cpp | 2 +- 19 files changed, 845 insertions(+), 8 deletions(-) create mode 100644 map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp create mode 100644 map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp rename map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/{vals => validators}/missing_regulatory_elements.hpp (91%) rename map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/{vals => validators}/regulatory_element_details.hpp (90%) create mode 100644 map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp create mode 100644 map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp create mode 100644 map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp create mode 100644 map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/validator_template.hpp create mode 100644 map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp create mode 100644 map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp rename map/autoware_lanelet2_map_validator/src/lib/{vals => validators}/missing_regulatory_elements.cpp (99%) rename map/autoware_lanelet2_map_validator/src/lib/{vals => validators}/regulatory_element_details.cpp (99%) create mode 100644 map/autoware_lanelet2_map_validator/src/lib/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp create mode 100644 map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/missing_regulatory_elements_for_traffic_light.cpp create mode 100644 map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp create mode 100644 map/autoware_lanelet2_map_validator/src/lib/validators/validator_template.cpp diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/cli.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/cli.hpp index f8aafee4..d1cedc89 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/cli.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/cli.hpp @@ -32,6 +32,7 @@ struct MetaConfig { lanelet::validation::CommandLineConfig command_line_config; std::string projector_type; + bool read_yaml = false; }; MetaConfig parseCommandLine(int argc, const char * argv[]); diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp new file mode 100644 index 00000000..26e4006b --- /dev/null +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp @@ -0,0 +1,41 @@ +// Copyright 2024 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ + +#include +#include + +namespace lanelet +{ +namespace validation +{ +class MissingRegulatoryElementsForCrosswalksValidator : public lanelet::validation::MapValidator +{ +public: + + constexpr static const char * name() { return "mapping.crosswalk.missing_regulatory_elements"; } + + lanelet::validation::Issues operator()(const lanelet::LaneletMap & map) override; + +private: + lanelet::validation::Issues checkMissingRegulatoryElementsForCrosswalks( + const lanelet::LaneletMap & map); + +}; +} // namespace validation +} // namespace lanelet + +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ \ No newline at end of file diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp new file mode 100644 index 00000000..d2965715 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp @@ -0,0 +1,39 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALK_HPP_ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALK_HPP_ + +#include +#include + +namespace lanelet +{ +namespace validation +{ +class RegulatoryElementsDetailsForCrosswalksValidator : public lanelet::validation::MapValidator +{ +public: + // Write the validator's name here + constexpr static const char * name() { return "mapping.crosswalk.regulatory_element_details"; } + + lanelet::validation::Issues operator()(const lanelet::LaneletMap & map) override; + +private: + lanelet::validation::Issues checkRegulatoryElementOfCrosswalks(const lanelet::LaneletMap & map); +}; +} // namespace validation +} // namespace lanelet + +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALK_HPP_ \ No newline at end of file diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/vals/missing_regulatory_elements.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/missing_regulatory_elements.hpp similarity index 91% rename from map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/vals/missing_regulatory_elements.hpp rename to map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/missing_regulatory_elements.hpp index c47a848c..71308a0a 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/vals/missing_regulatory_elements.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/missing_regulatory_elements.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALS__MISSING_REGULATORY_ELEMENTS_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALS__MISSING_REGULATORY_ELEMENTS_HPP_ +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__MISSING_REGULATORY_ELEMENTS_HPP_ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__MISSING_REGULATORY_ELEMENTS_HPP_ #include "autoware_lanelet2_map_validator/utils.hpp" diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/vals/regulatory_element_details.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/regulatory_element_details.hpp similarity index 90% rename from map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/vals/regulatory_element_details.hpp rename to map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/regulatory_element_details.hpp index 0bce6919..3333eae7 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/vals/regulatory_element_details.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/regulatory_element_details.hpp @@ -29,8 +29,8 @@ namespace lanelet namespace validation { -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALS__REGULATORY_ELEMENT_DETAILS_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALS__REGULATORY_ELEMENT_DETAILS_HPP_ +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__REGULATORY_ELEMENT_DETAILS_HPP_ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__REGULATORY_ELEMENT_DETAILS_HPP_ class RegulatoryElementDetailsChecker : public lanelet::validation::MapValidator { diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp new file mode 100644 index 00000000..70560b76 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp @@ -0,0 +1,40 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ + +#include +#include + +namespace lanelet +{ +namespace validation +{ +class MissingRegulatoryElementsForStopLinesValidator : public lanelet::validation::MapValidator +{ +public: + + constexpr static const char * name() { return "mapping.stop_line.missing_regulatory_elements"; } + + lanelet::validation::Issues operator()(const lanelet::LaneletMap & map) override; + +private: + lanelet::validation::Issues checkMissingRegulatoryElementsForStopLines( + const lanelet::LaneletMap & map); +}; +} // namespace validation +} // namespace lanelet + +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ \ No newline at end of file diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp new file mode 100644 index 00000000..72d96af4 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp @@ -0,0 +1,40 @@ +// Copyright 2024 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ + +#include +#include + +namespace lanelet +{ +namespace validation +{ +class MissingRegulatoryElementsForTrafficLightsValidator : public lanelet::validation::MapValidator +{ +public: + + constexpr static const char * name() { return "mapping.traffic_light.missing_regulatory_elements"; } + + lanelet::validation::Issues operator()(const lanelet::LaneletMap & map) override; + +private: + lanelet::validation::Issues checkMissingRegulatoryElementsForTrafficLights( + const lanelet::LaneletMap & map); +}; +} // namespace validation +} // namespace lanelet + +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ \ No newline at end of file diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp new file mode 100644 index 00000000..5b50624f --- /dev/null +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp @@ -0,0 +1,42 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHTS__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHTS__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ + +#include +#include + +#include + +namespace lanelet +{ +namespace validation +{ +class RegulatoryElementsDetailsForTrafficLightsValidator : public lanelet::validation::MapValidator +{ +public: + // Write the validator's name here + constexpr static const char * name() { return "mapping.traffic_light.regulatory_element_details"; } + + lanelet::validation::Issues operator()(const lanelet::LaneletMap & map) override; + +private: + bool isPedestrianTrafficLight(const std::vector & traffic_lights); + lanelet::validation::Issues checkRegulatoryElementOfTrafficLights(const lanelet::LaneletMap & map); +}; +} // namespace validation +} // namespace lanelet + +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHTS__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ \ No newline at end of file diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/validator_template.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/validator_template.hpp new file mode 100644 index 00000000..20a71100 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/validator_template.hpp @@ -0,0 +1,38 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__VALIDATOR_TEMPLATE_HPP_ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__VALIDATOR_TEMPLATE_HPP_ + +#include +#include + +namespace lanelet +{ +namespace validation +{ +class ValidatorTemplate : public lanelet::validation::MapValidator +{ +public: + // Write the validator's name here + constexpr static const char * name() { return "mapping.validator.template"; } + + lanelet::validation::Issues operator()(const lanelet::LaneletMap & map) override; + +private: +}; +} // namespace validation +} // namespace lanelet + +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__VALIDATOR_TEMPLATE_HPP_ \ No newline at end of file diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp new file mode 100644 index 00000000..28f6e738 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp @@ -0,0 +1,124 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include + +#include + +#include + +#include + +namespace lanelet +{ +namespace validation +{ +namespace +{ + lanelet::validation::RegisterMapValidator reg; +} + + lanelet::validation::Issues MissingRegulatoryElementsForCrosswalksValidator::operator()( + const lanelet::LaneletMap & map) + { + lanelet::validation::Issues issues; + + lanelet::autoware::validation::appendIssues( + issues, checkMissingRegulatoryElementsForCrosswalks(map)); + + return issues; + } + + lanelet::validation::Issues + MissingRegulatoryElementsForCrosswalksValidator::checkMissingRegulatoryElementsForCrosswalks( + const lanelet::LaneletMap & map) + { + lanelet::validation::Issues issues; + + // Get all lanelets whose type is crosswalk + std::set cw_ids; + std::set tl_elem_with_cw_; + for (const auto & ll : map.laneletLayer) { + const auto & attrs = ll.attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + // Check if this lanelet is crosswalk + if (it != attrs.end() && it->second == lanelet::AttributeValueString::Crosswalk) { + cw_ids.insert(ll.id()); + + // Check if crosswalk has reg elem of traffic light + for (const auto & elem : ll.regulatoryElements()) { + const auto & attrs = elem->attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + if (it != attrs.end() && it->second == lanelet::AttributeValueString::TrafficLight) { + tl_elem_with_cw_.insert(elem->id()); + } + } + } + } + + std::cout << "cw_ids" << std::endl; + for (const auto & id : cw_ids) { + std::cout << id << std::endl; + } + + std::cout << "tl_elem_with_cw_" << std::endl; + for (const auto & id : tl_elem_with_cw_) { + std::cout << id << std::endl; + } + + // Filter regulatory elements whose type is crosswalk and has refers + auto reg_elem_cw = + map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { + const auto & attrs = elem->attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + return it != attrs.end() && it->second == lanelet::AttributeValueString::Crosswalk; + }) | + ranges::views::filter([](auto && elem) { + const auto & param = elem->getParameters(); + return param.find(lanelet::RoleNameString::Refers) != param.end(); + }); + + std::cout << "reg_elem_cw" << std::endl; + for (const auto & id : reg_elem_cw) { + std::cout << id << std::endl; + } + + // Get all lanelets of crosswalk referred by regulatory elements + std::set cw_ids_reg_elem; + for (const auto & elem : reg_elem_cw) { + const auto & refers = elem->getParameters(lanelet::RoleName::Refers); + for (const lanelet::ConstLanelet & refer : refers) { + cw_ids_reg_elem.insert(refer.id()); + } + } + + std::cout << "cw_ids_reg_elem" << std::endl; + for (const auto & id : cw_ids_reg_elem) { + std::cout << id << std::endl; + } + + // Check if all lanelets of crosswalk referred by regulatory elements + for (const auto & cw_id : cw_ids) { + if (cw_ids_reg_elem.find(cw_id) == cw_ids_reg_elem.end()) { + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::Lanelet, cw_id, + "No regulatory element refers to this crosswalk."); + } + } + + return issues; + } +} // namespace validation +} // namespace lanelet2 \ No newline at end of file diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp new file mode 100644 index 00000000..05f56a80 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp @@ -0,0 +1,123 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + + +#include + +#include +#include + +#include + +#include +#include + +namespace lanelet +{ +namespace validation +{ +namespace +{ +lanelet::validation::RegisterMapValidator reg; +} // namespace + + lanelet::validation::Issues RegulatoryElementsDetailsForCrosswalksValidator::operator()( + const lanelet::LaneletMap & map) + { + // All issues found by all validators + lanelet::validation::Issues issues; + + // Append issues found by each validator + lanelet::autoware::validation::appendIssues(issues, checkRegulatoryElementOfCrosswalks(map)); + return issues; + } + + lanelet::validation::Issues RegulatoryElementsDetailsForCrosswalksValidator::checkRegulatoryElementOfCrosswalks( + const lanelet::LaneletMap & map) + { + lanelet::validation::Issues issues; + // filter elem whose Subtype is crosswalk + auto elems = map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { + const auto & attrs = elem->attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + return it != attrs.end() && it->second == lanelet::AttributeValueString::Crosswalk; + }); + + for (const auto & elem : elems) { + // Get lanelet of crosswalk referred by regulatory element + auto refers = elem->getParameters(lanelet::RoleName::Refers); + // Get stop line referred by regulatory element + auto ref_lines = elem->getParameters(lanelet::RoleName::RefLine); + // Get crosswalk polygon referred by regulatory element + auto crosswalk_polygons = elem->getParameters( + lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon); + + const auto & issue_cw = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::Lanelet, + lanelet::utils::getId(), + "Refers of crosswalk regulatory element must have type of crosswalk."); + lanelet::autoware::validation::checkPrimitivesType( + refers, lanelet::AttributeValueString::Lanelet, lanelet::AttributeValueString::Crosswalk, + issue_cw, issues); + + const auto & issue_sl = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, + lanelet::utils::getId(), + "Refline of crosswalk regulatory element must have type of stopline."); + lanelet::autoware::validation::checkPrimitivesType( + ref_lines, lanelet::AttributeValueString::StopLine, issue_sl, issues); + + const auto & issue_poly = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::Polygon, + lanelet::utils::getId(), + "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon."); + lanelet::autoware::validation::checkPrimitivesType( + crosswalk_polygons, lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon, + issue_poly, issues); + + // Report warning if regulatory element does not have crosswalk polygon + if (crosswalk_polygons.empty()) { + issues.emplace_back( + lanelet::validation::Severity::Warning, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), "Regulatory element of cross walk is nice to have crosswalk_polygon."); + } else if (crosswalk_polygons.size() > 1) { // Report error if regulatory element has two or + // more crosswalk polygon + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), "Regulatory element of cross walk must have only one crosswalk_polygon."); + } + // Report Info if regulatory element does not have stop line + if (ref_lines.empty()) { + issues.emplace_back( + lanelet::validation::Severity::Info, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), "Regulatory element of cross walk does not have stop line(ref_line)."); + } + // Report error if regulatory element does not have lanelet of crosswalk + if (refers.empty()) { + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), "Regulatory element of cross walk must have lanelet of crosswalk(refers)."); + } else if (refers.size() > 1) { // Report error if regulatory element has two or more lanelet + // of crosswalk + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), + "Regulatory element of cross walk must have only one lanelet of crosswalk(refers)."); + } + } + return issues; + } + +} // namespace validation +} // namespace lanelet diff --git a/map/autoware_lanelet2_map_validator/src/lib/vals/missing_regulatory_elements.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/missing_regulatory_elements.cpp similarity index 99% rename from map/autoware_lanelet2_map_validator/src/lib/vals/missing_regulatory_elements.cpp rename to map/autoware_lanelet2_map_validator/src/lib/validators/missing_regulatory_elements.cpp index d7a26054..bd23d75a 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/vals/missing_regulatory_elements.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/validators/missing_regulatory_elements.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include namespace lanelet { diff --git a/map/autoware_lanelet2_map_validator/src/lib/vals/regulatory_element_details.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/regulatory_element_details.cpp similarity index 99% rename from map/autoware_lanelet2_map_validator/src/lib/vals/regulatory_element_details.cpp rename to map/autoware_lanelet2_map_validator/src/lib/validators/regulatory_element_details.cpp index af5ca168..75883768 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/vals/regulatory_element_details.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/validators/regulatory_element_details.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_lanelet2_map_validator/vals/regulatory_element_details.hpp" +#include "autoware_lanelet2_map_validator/validators/regulatory_element_details.hpp" namespace lanelet { diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp new file mode 100644 index 00000000..3535a55f --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/lib/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp @@ -0,0 +1,94 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include + +#include +#include +#include + +#include + +#include + +namespace lanelet +{ +namespace validation +{ +namespace +{ + lanelet::validation::RegisterMapValidator reg; +} + + lanelet::validation::Issues MissingRegulatoryElementsForStopLinesValidator::operator()( + const lanelet::LaneletMap & map) + { + lanelet::validation::Issues issues; + + lanelet::autoware::validation::appendIssues( + issues, checkMissingRegulatoryElementsForStopLines(map)); + + return issues; + } + + lanelet::validation::Issues + MissingRegulatoryElementsForStopLinesValidator::checkMissingRegulatoryElementsForStopLines( + const lanelet::LaneletMap & map) + { + lanelet::validation::Issues issues; + + // Get all line strings whose type is stop line + auto sl_ids = map.lineStringLayer | ranges::views::filter([](auto && ls) { + const auto & attrs = ls.attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Type); + return it != attrs.end() && it->second == lanelet::AttributeValueString::StopLine; + }) | + ranges::views::transform([](auto && ls) { return ls.id(); }) | + ranges::views::unique; + + // Filter regulatory elements whose refline type is stop line + auto reg_elem_sl = map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { + const auto & params = elem->getParameters(); + return params.find(lanelet::RoleNameString::RefLine) != params.end(); + }); + + // Get all line strings of stop line referred by regulatory elements + std::set sl_ids_reg_elem; + for (const auto & elem : reg_elem_sl) { + const auto & ref_lines = + elem->getParameters(lanelet::RoleName::RefLine); + for (const auto & ref_line : ref_lines) { + const auto & attrs = ref_line.attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Type); + if (it != attrs.end() && it->second == lanelet::AttributeValueString::StopLine) { + sl_ids_reg_elem.insert(ref_line.id()); + } + } + } + + // Check if all line strings of stop line referred by regulatory elements + for (const auto & sl_id : sl_ids) { + if (sl_ids_reg_elem.find(sl_id) == sl_ids_reg_elem.end()) { + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, sl_id, + "No regulatory element refers to this stop walk."); + } + } + + return issues; + } + +} // namespace validation +} // namespace lanelet2 \ No newline at end of file diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/missing_regulatory_elements_for_traffic_light.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/missing_regulatory_elements_for_traffic_light.cpp new file mode 100644 index 00000000..1c6b177e --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/missing_regulatory_elements_for_traffic_light.cpp @@ -0,0 +1,109 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include + +#include +#include +#include + +#include + +#include + +namespace lanelet +{ +namespace validation +{ +namespace +{ + lanelet::validation::RegisterMapValidator reg; +} + + lanelet::validation::Issues MissingRegulatoryElementsForTrafficLightsValidator::operator()( + const lanelet::LaneletMap & map) + { + lanelet::validation::Issues issues; + + lanelet::autoware::validation::appendIssues( + issues, checkMissingRegulatoryElementsForTrafficLights(map)); + + return issues; + } + + lanelet::validation::Issues + MissingRegulatoryElementsForTrafficLightsValidator::checkMissingRegulatoryElementsForTrafficLights( + const lanelet::LaneletMap & map) + { + lanelet::validation::Issues issues; + + // Get all line strings whose type is traffic light + auto tl_ids = + map.lineStringLayer | ranges::views::filter([](auto && ls) { + const auto & attrs = ls.attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Type); + return it != attrs.end() && it->second == lanelet::AttributeValueString::TrafficLight; + }) | + ranges::views::transform([](auto && ls) { return ls.id(); }) | ranges::views::unique; + + std::cout << "tl_ids" << std::endl; + std::cout << typeid(decltype(tl_ids)).name() << std::endl; + for (const auto & id : tl_ids) { + std::cout << id << std::endl; + } + + // Filter regulatory elements whose type is traffic light and has refers + auto reg_elem_tl = map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { + const auto & attrs = elem->attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + const auto & params = elem->getParameters(); + return it != attrs.end() && + it->second == lanelet::AttributeValueString::TrafficLight && + params.find(lanelet::RoleNameString::Refers) != params.end(); + }); + std::cout << "reg_elem_tl" << std::endl; + for (const auto & id : reg_elem_tl) { + std::cout << id << std::endl; + } + + // Get all line strings of traffic light referred by regulatory elements + std::set tl_ids_reg_elem; + for (const auto & elem : reg_elem_tl) { + const auto & refers = + elem->getParameters(lanelet::RoleName::Refers); + for (const auto & refer : refers) { + tl_ids_reg_elem.insert(refer.id()); + } + } + + std::cout << "tl_ids_reg_elem" << std::endl; + for (const auto & id : tl_ids_reg_elem) { + std::cout << id << std::endl; + } + + // Check if all line strings of traffic light referred by regulatory elements + for (const auto & tl_id : tl_ids) { + if (tl_ids_reg_elem.find(tl_id) == tl_ids_reg_elem.end()) { + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, tl_id, + "No regulatory element refers to this traffic light."); + } + } + + return issues; + } + +} // namespace validation +} // namespace lanelet2 \ No newline at end of file diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp new file mode 100644 index 00000000..41145d2f --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp @@ -0,0 +1,112 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include +#include + +#include +#include + +namespace lanelet +{ +namespace validation +{ +namespace +{ +lanelet::validation::RegisterMapValidator reg; +} // namespace + + lanelet::validation::Issues RegulatoryElementsDetailsForTrafficLightsValidator::operator()( + const lanelet::LaneletMap & map) + { + // All issues found by all validators + lanelet::validation::Issues issues; + + // Append issues found by each validator + lanelet::autoware::validation::appendIssues(issues, checkRegulatoryElementOfTrafficLights(map)); + return issues; + } + + bool RegulatoryElementsDetailsForTrafficLightsValidator::isPedestrianTrafficLight( + const std::vector & traffic_lights) + { + for (const auto & tl : traffic_lights) { + const auto & attrs = tl.attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + if (it == attrs.end() || it->second != "red_green") { + return false; + } + } + return true; + } + + lanelet::validation::Issues RegulatoryElementsDetailsForTrafficLightsValidator::checkRegulatoryElementOfTrafficLights( + const lanelet::LaneletMap & map) + { + lanelet::validation::Issues issues; + // filter regulatory element whose Subtype is traffic light + auto elems = + map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { + const auto & attrs = elem->attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + return it != attrs.end() && it->second == lanelet::AttributeValueString::TrafficLight; + }); + + for (const auto & elem : elems) { + // Get line strings of traffic light referred by regulatory element + auto refers = elem->getParameters(lanelet::RoleName::Refers); + // Get stop line referred by regulatory element + auto ref_lines = elem->getParameters(lanelet::RoleName::RefLine); + const auto & issue_tl = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, + lanelet::utils::getId(), + "Refers of traffic light regulatory element must have type of traffic_light."); + lanelet::autoware::validation::checkPrimitivesType( + refers, lanelet::AttributeValueString::TrafficLight, issue_tl, issues); + + const auto & issue_sl = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, + lanelet::utils::getId(), + "Refline of traffic light regulatory element must have type of stop_line."); + lanelet::autoware::validation::checkPrimitivesType( + ref_lines, lanelet::AttributeValueString::StopLine, issue_sl, issues); + + if (refers.empty()) { + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), "Regulatory element of traffic light must have a traffic light(refers)."); + } + // TODO(sgk-000): Check correct behavior if regulatory element has two or more traffic light + // else if (refers.size() != 1) { + // issues.emplace_back( + // lanelet::validation::Severity::Error, + // lanelet::validation::Primitive::RegulatoryElement, elem->id(), "Regulatory element of + // traffic light must have only one traffic light(refers)."); + // } + + // Report error if regulatory element does not have stop line and this is not a pedestrian + // traffic light + if (ref_lines.empty() && !isPedestrianTrafficLight(refers)) { + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), "Regulatory element of traffic light must have a stop line(ref_line)."); + } + } + return issues; + } + +} // namespace validation +} // namespace lanelet diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/validator_template.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/validator_template.cpp new file mode 100644 index 00000000..0984d49c --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/lib/validators/validator_template.cpp @@ -0,0 +1,34 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +namespace lanelet +{ +namespace validation +{ + lanelet::validation::RegisterMapValidator reg; + + lanelet::validation::Issues ValidatorTemplate::operator()( + const lanelet::LaneletMap & map) + { + lanelet::validation::Issues issues; + + // Remove this line and write down how to append issues + (void)map; + + return issues; + } +} +} \ No newline at end of file diff --git a/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp index a5a1da18..bf3dfcf0 100644 --- a/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp +++ b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_lanelet2_map_validator/vals/missing_regulatory_elements.hpp" +#include "autoware_lanelet2_map_validator/validators/missing_regulatory_elements.hpp" #include diff --git a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp index b9a98e25..6600bd5f 100644 --- a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp +++ b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_lanelet2_map_validator/vals/regulatory_element_details.hpp" +#include "autoware_lanelet2_map_validator/validators/regulatory_element_details.hpp" #include From ebefd7c14471432a757ad4a49549cdf2ee028e4d Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Thu, 19 Sep 2024 17:06:00 +0900 Subject: [PATCH 07/45] Split the validation code into smaller pieces. Added yaml input/output for a set of validations Signed-off-by: TaikiYamada4 --- .../CMakeLists.txt | 4 +- .../autoware_lanelet2_map_validator/cli.hpp | 3 +- .../package.xml | 2 + .../src/lib/cli.cpp | 60 ++++--- .../src/lib/validation.cpp | 2 +- ...sing_regulatory_elements_for_crosswalk.cpp | 20 --- ..._regulatory_elements_for_traffic_light.cpp | 15 -- .../src/new_main.cpp | 165 ++++++++++++++++++ .../src/test_regulatory_element_details.cpp | 24 ++- 9 files changed, 230 insertions(+), 65 deletions(-) create mode 100644 map/autoware_lanelet2_map_validator/src/new_main.cpp diff --git a/map/autoware_lanelet2_map_validator/CMakeLists.txt b/map/autoware_lanelet2_map_validator/CMakeLists.txt index 422dfeb8..a4d86f2c 100644 --- a/map/autoware_lanelet2_map_validator/CMakeLists.txt +++ b/map/autoware_lanelet2_map_validator/CMakeLists.txt @@ -5,6 +5,7 @@ find_package(autoware_cmake REQUIRED) autoware_package() ament_auto_find_build_dependencies() +find_package(yaml-cpp REQUIRED) include_directories( include @@ -15,10 +16,11 @@ ament_auto_add_library(autoware_lanelet2_map_validator_lib SHARED ${autoware_lanelet2_map_validator_lib_src} ) -ament_auto_add_executable(autoware_lanelet2_map_validator src/main.cpp) +ament_auto_add_executable(autoware_lanelet2_map_validator src/new_main.cpp) add_dependencies(autoware_lanelet2_map_validator autoware_lanelet2_map_validator_lib) target_link_libraries(autoware_lanelet2_map_validator autoware_lanelet2_map_validator_lib + yaml-cpp ) if(BUILD_TESTING) diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/cli.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/cli.hpp index d1cedc89..6e90868f 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/cli.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/cli.hpp @@ -32,7 +32,8 @@ struct MetaConfig { lanelet::validation::CommandLineConfig command_line_config; std::string projector_type; - bool read_yaml = false; + std::string requirements_file; + std::string output_file_path; }; MetaConfig parseCommandLine(int argc, const char * argv[]); diff --git a/map/autoware_lanelet2_map_validator/package.xml b/map/autoware_lanelet2_map_validator/package.xml index 5a657672..6930eb3d 100644 --- a/map/autoware_lanelet2_map_validator/package.xml +++ b/map/autoware_lanelet2_map_validator/package.xml @@ -10,6 +10,8 @@ ament_cmake_auto autoware_cmake + yaml-cpp + autoware_lanelet2_extension lanelet2_core lanelet2_io diff --git a/map/autoware_lanelet2_map_validator/src/lib/cli.cpp b/map/autoware_lanelet2_map_validator/src/lib/cli.cpp index 11f8c4d6..80da4ec9 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/cli.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/cli.cpp @@ -34,36 +34,42 @@ MetaConfig parseCommandLine(int argc, const char * argv[]) ("map_file,m", po::value(), "Path to the map to be validated") - ("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") + ("requirements_file,r", po::value(), + "Path to the yaml file where the list of requirements and validations is written") - ("projector,p", po::value(&config.projector_type)->composing(), - "Projector used for loading lanelet map. Available projectors are: mgrs, utm, " - "transverse_mercator. (default: mgrs)") + ("output_file_path,o", po::value(), + "Path of the yaml file where the list of validation results will be written") - ("location,l", - po::value(&validation_config.location)->default_value(validation_config.location), - "Location of the map (for instanciating the traffic rules), e.g. de for Germany") + ("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") - ("participants", po::value(&validation_config.participants)->composing(), - "Participants for which the routing graph will be instanciated (default: vehicle)") + ("projector,p", po::value(&config.projector_type)->composing(), + "Projector used for loading lanelet map. Available projectors are: mgrs, utm, " + "transverse_mercator. (default: mgrs)") - ("lat", - po::value(&validation_config.origin.lat) - ->default_value(validation_config.origin.lat), - "latitude coordinate of map origin. This is reguired for the transverse mercator " - "and utm projector.") + ("location,l", + po::value(&validation_config.location)->default_value(validation_config.location), + "Location of the map (for instanciating the traffic rules), e.g. de for Germany") - ("lon", - po::value(&validation_config.origin.lon) - ->default_value(validation_config.origin.lon), - "longitude coofdinate of map origin. This is reguired for the transverse mercator " - "and utm projector.") + ("participants", po::value(&validation_config.participants)->composing(), + "Participants for which the routing graph will be instanciated (default: vehicle)") - ("print", "Only print all avalible checker, but dont run them"); + ("lat", + po::value(&validation_config.origin.lat) + ->default_value(validation_config.origin.lat), + "latitude coordinate of map origin. This is reguired for the transverse mercator " + "and utm projector.") + + ("lon", + po::value(&validation_config.origin.lon) + ->default_value(validation_config.origin.lon), + "longitude coofdinate of map origin. This is reguired for the transverse mercator " + "and utm projector.") + + ("print", "Only print all avalible checker, but dont run them"); po::variables_map vm; po::positional_options_description pos; pos.add("map_file", 1); @@ -75,6 +81,12 @@ MetaConfig parseCommandLine(int argc, const char * argv[]) config.command_line_config.mapFile = vm["map_file"].as(); } + if (vm.count("requirements_file") != 0) { + config.requirements_file = vm["requirements_file"].as(); + } + if (vm.count("output_file_path") != 0) { + config.output_file_path = vm["output_file_path"].as(); + } if ( (vm.count("lat") != 0 && vm.count("lon") != 0) && (config.projector_type == "tm" || config.projector_type == "utm")) { diff --git a/map/autoware_lanelet2_map_validator/src/lib/validation.cpp b/map/autoware_lanelet2_map_validator/src/lib/validation.cpp index f09a447b..e12a86be 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validation.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/validation.cpp @@ -35,7 +35,7 @@ std::unique_ptr getProjector(const MetaConfig & config) } else if (config.projector_type == projector_names::utm) { return std::make_unique(lanelet::Origin{val_config.origin}); } else { - std::cerr << "Set to default projector: MGRS projector" << std::endl; + //std::cerr << "Set to default projector: MGRS projector" << std::endl; return std::make_unique(); } } diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp index 28f6e738..714e153a 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp @@ -68,16 +68,6 @@ namespace } } - std::cout << "cw_ids" << std::endl; - for (const auto & id : cw_ids) { - std::cout << id << std::endl; - } - - std::cout << "tl_elem_with_cw_" << std::endl; - for (const auto & id : tl_elem_with_cw_) { - std::cout << id << std::endl; - } - // Filter regulatory elements whose type is crosswalk and has refers auto reg_elem_cw = map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { @@ -90,11 +80,6 @@ namespace return param.find(lanelet::RoleNameString::Refers) != param.end(); }); - std::cout << "reg_elem_cw" << std::endl; - for (const auto & id : reg_elem_cw) { - std::cout << id << std::endl; - } - // Get all lanelets of crosswalk referred by regulatory elements std::set cw_ids_reg_elem; for (const auto & elem : reg_elem_cw) { @@ -104,11 +89,6 @@ namespace } } - std::cout << "cw_ids_reg_elem" << std::endl; - for (const auto & id : cw_ids_reg_elem) { - std::cout << id << std::endl; - } - // Check if all lanelets of crosswalk referred by regulatory elements for (const auto & cw_id : cw_ids) { if (cw_ids_reg_elem.find(cw_id) == cw_ids_reg_elem.end()) { diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/missing_regulatory_elements_for_traffic_light.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/missing_regulatory_elements_for_traffic_light.cpp index 1c6b177e..50a3146c 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/missing_regulatory_elements_for_traffic_light.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/missing_regulatory_elements_for_traffic_light.cpp @@ -58,12 +58,6 @@ namespace }) | ranges::views::transform([](auto && ls) { return ls.id(); }) | ranges::views::unique; - std::cout << "tl_ids" << std::endl; - std::cout << typeid(decltype(tl_ids)).name() << std::endl; - for (const auto & id : tl_ids) { - std::cout << id << std::endl; - } - // Filter regulatory elements whose type is traffic light and has refers auto reg_elem_tl = map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { const auto & attrs = elem->attributes(); @@ -73,10 +67,6 @@ namespace it->second == lanelet::AttributeValueString::TrafficLight && params.find(lanelet::RoleNameString::Refers) != params.end(); }); - std::cout << "reg_elem_tl" << std::endl; - for (const auto & id : reg_elem_tl) { - std::cout << id << std::endl; - } // Get all line strings of traffic light referred by regulatory elements std::set tl_ids_reg_elem; @@ -88,11 +78,6 @@ namespace } } - std::cout << "tl_ids_reg_elem" << std::endl; - for (const auto & id : tl_ids_reg_elem) { - std::cout << id << std::endl; - } - // Check if all line strings of traffic light referred by regulatory elements for (const auto & tl_id : tl_ids) { if (tl_ids_reg_elem.find(tl_id) == tl_ids_reg_elem.end()) { diff --git a/map/autoware_lanelet2_map_validator/src/new_main.cpp b/map/autoware_lanelet2_map_validator/src/new_main.cpp new file mode 100644 index 00000000..905b4950 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/new_main.cpp @@ -0,0 +1,165 @@ +// Copyright 2024 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include +#include "lanelet2_validation/Validation.h" + +#include +#include +#include + +// ANSI color codes for console output +#define BOLD_ONLY "\033[1m" +#define BOLD_GREEN "\033[1;32m" +#define BOLD_YELLOW "\033[1;33m" +#define BOLD_RED "\033[1;31m" +#define NORMAL_GREEN "\033[32m" +#define NORMAL_RED "\033[31m" +#define FONT_RESET "\033[0m" + +int process_requirements(YAML::Node yaml_config, const lanelet::autoware::validation::MetaConfig& validator_config) { + unsigned long warning_count = 0; + unsigned long error_count = 0; + lanelet::autoware::validation::MetaConfig temp_validator_config = validator_config; + + for (YAML::Node requirement : yaml_config["requirements"]) { + std::string id = requirement["id"].as(); + bool requirement_passed = true; + + std::vector issues; + std::map temp_validation_results; + + for (YAML::Node validator : requirement["validators"]) { + std::string validator_name = validator["name"].as(); + temp_validator_config.command_line_config.validationConfig.checksFilter = validator_name; + + std::vector temp_issues = lanelet::autoware::validation::validateMap(temp_validator_config); + + if (temp_issues.empty()) { + // Validator passed + temp_validation_results[validator_name] = true; + validator["passed"] = true; + } else { + // Validator failed + requirement_passed = false; + warning_count += temp_issues[0].warnings().size(); + error_count += temp_issues[0].errors().size(); + temp_validation_results[validator_name] = false; + validator["passed"] = false; + YAML::Node issues_node = YAML::Node(YAML::NodeType::Sequence); + for (lanelet::validation::Issue issue : temp_issues[0].issues) { + YAML::Node issue_node; + issue_node["severity"] = lanelet::validation::toString(issue.severity); + issue_node["primitive"] = lanelet::validation::toString(issue.primitive); + issue_node["id"] = issue.id; + issue_node["message"] = issue.message; + issues_node.push_back(issue_node); + } + validator["issues"] = issues_node; + } + + lanelet::autoware::validation::appendIssues(issues, std::move(temp_issues)); + } + + std::cout << BOLD_ONLY << "[" << id << "] "; + + if (requirement_passed) { + requirement["passed"] = true; + std::cout << BOLD_GREEN << "Passed" << FONT_RESET << std::endl; + } else { + requirement["passed"] = false; + std::cout << BOLD_RED << "Failed" << FONT_RESET << std::endl; + } + + // In order to make "passed" field above then the "validators" field in the output file. + YAML::Node temp_validators = requirement["validators"]; + requirement.remove("validators"); + requirement["validators"] = temp_validators; + + for (const auto &result : temp_validation_results) { + if (result.second) { + std::cout << " - " << result.first << ": " << NORMAL_GREEN << "Passed" << FONT_RESET << std::endl; + } else { + std::cout << " - " << result.first << ": " << NORMAL_RED << "Failed" << FONT_RESET << std::endl; + } + } + lanelet::validation::printAllIssues(issues); + std::cout << std::endl; + } + + if(warning_count + error_count == 0) { + std::cout << BOLD_GREEN << "No issues were found from " << FONT_RESET << validator_config.command_line_config.mapFile << std::endl; + } else { + if (warning_count > 0) { + std::cout << BOLD_YELLOW << "Total of " << warning_count << " warnings were found from " << FONT_RESET << validator_config.command_line_config.mapFile << std::endl; + } + if (error_count > 0) { + std::cout << BOLD_RED << "Total of " << error_count << " errors were found from " << FONT_RESET << validator_config.command_line_config.mapFile << std::endl; + } + } + + if (!validator_config.output_file_path.empty()) { + std::string file_name = validator_config.output_file_path + "/lanelet2_validation_results.yaml"; + std::ofstream fout(file_name); + fout << yaml_config; + std::cout << "Results are output to " << file_name << std::endl; + } + + return (warning_count + error_count == 0) ? 0 : 1; +} + +int main(int argc, char * argv[]) +{ + lanelet::autoware::validation::MetaConfig config = lanelet::autoware::validation::parseCommandLine( + argc, const_cast(argv)); // NOLINT + + // Print help (Already done in parseCommandLine) + if (config.command_line_config.help) { + return 0; + } + + // Print available validators + if (config.command_line_config.print) { + auto checks = + lanelet::validation::availabeChecks(config.command_line_config.validationConfig.checksFilter); + if (checks.empty()) { + std::cout << "No checks found matching '" << config.command_line_config.validationConfig.checksFilter + << "'\n"; + } else { + std::cout << "The following checks are available:\n"; + for (auto & check : checks) { + std::cout << check << '\n'; + } + } + return 0; + } + + // Check whether the map_file is specified + if (config.command_line_config.mapFile.empty()) { + std::cout << "No map file specified" << std::endl; + return 1; + } + + // Validation start + if (!config.requirements_file.empty()) { + YAML::Node yaml_config = YAML::LoadFile(config.requirements_file); + return process_requirements(yaml_config, config); + } else { + auto issues = lanelet::autoware::validation::validateMap(config); + lanelet::validation::printAllIssues(issues); + return static_cast(!issues.empty()); + } +} diff --git a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp index 6600bd5f..41de8ded 100644 --- a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp +++ b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp @@ -14,6 +14,9 @@ #include "autoware_lanelet2_map_validator/validators/regulatory_element_details.hpp" +#include +#include + #include using lanelet::AttributeMap; @@ -136,12 +139,27 @@ class TestSuite : public ::testing::Test TEST_F(TestSuite, ValidatorAvailability) // NOLINT for gtest { + std::string expected_validators_concat = + "mapping.crosswalk.missing_regulatory_elements," + "mapping.stop_line.missing_regulatory_elements," + "mapping.traffic_light.missing_regulatory_elements"; + lanelet::validation::Strings validators = lanelet::validation::availabeChecks( - lanelet::validation::RegulatoryElementDetailsChecker::name()); - uint8_t expected_num_validators = 1; + target_validators); + uint8_t expected_num_validators = 3; + std::cout << "size: " << validators.size() << std::endl; EXPECT_EQ(expected_num_validators, validators.size()); + + std::set expected_validators_set = { + "mapping.crosswalk.missing_regulatory_elements", + "mapping.stop_line.missing_regulatory_elements", + "mapping.traffic_light.missing_regulatory_elements" + }; + for (const auto & v : validators) { - EXPECT_EQ(lanelet::validation::RegulatoryElementDetailsChecker::name(), v); + std::cout << v.name() << std::endl; + EXPECT_TRUE(expected_validators_set.find(v.name()) != expected_validators_set.end()) + << "Unexpected validator found: " << v.name(); } } From ea38dd143ac4e1d5922e9436732a693e5e55e213 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Thu, 19 Sep 2024 18:18:54 +0900 Subject: [PATCH 08/45] Fixed test codes to use the separated codes Signed-off-by: TaikiYamada4 --- ...ing_regulatory_elements_for_stop_lines.cpp | 2 +- .../src/test_missing_regulatory_elements.cpp | 42 +++++++++++++++---- .../src/test_regulatory_element_details.cpp | 38 ++++++++++------- 3 files changed, 57 insertions(+), 25 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp index 3535a55f..1b6a9da0 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp @@ -83,7 +83,7 @@ namespace if (sl_ids_reg_elem.find(sl_id) == sl_ids_reg_elem.end()) { issues.emplace_back( lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, sl_id, - "No regulatory element refers to this stop walk."); + "No regulatory element refers to this stop line."); } } diff --git a/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp index bf3dfcf0..52da8ed9 100644 --- a/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp +++ b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp @@ -13,6 +13,9 @@ // limitations under the License. #include "autoware_lanelet2_map_validator/validators/missing_regulatory_elements.hpp" +#include +#include +#include #include @@ -129,19 +132,39 @@ class TestSuite : public ::testing::Test } } AttributeMap sl_attr_, tl_attr_, cw_attr_, cw_poly_attr_, tl_re_attr_, cw_re_attr_; - lanelet::validation::MissingRegulatoryElementsChecker checker_; private: }; TEST_F(TestSuite, ValidatorAvailability) // NOLINT for gtest { + std::string expected_validators_concat = + "mapping.crosswalk.missing_regulatory_elements," + "mapping.stop_line.missing_regulatory_elements," + "mapping.traffic_light.missing_regulatory_elements"; + lanelet::validation::Strings validators = lanelet::validation::availabeChecks( - lanelet::validation::MissingRegulatoryElementsChecker::name()); - uint8_t expected_num_validators = 1; + expected_validators_concat); + uint8_t expected_num_validators = 3; + std::cout << "size: " << validators.size() << std::endl; EXPECT_EQ(expected_num_validators, validators.size()); - for (const auto & v : validators) { - EXPECT_EQ(lanelet::validation::MissingRegulatoryElementsChecker::name(), v); + + std::set expected_validators_set = { + "mapping.crosswalk.missing_regulatory_elements", + "mapping.stop_line.missing_regulatory_elements", + "mapping.traffic_light.missing_regulatory_elements" + }; + + std::set testing_validators_set = { + lanelet::validation::MissingRegulatoryElementsForCrosswalksValidator::name(), + lanelet::validation::MissingRegulatoryElementsForStopLinesValidator::name(), + lanelet::validation::MissingRegulatoryElementsForTrafficLightsValidator::name() + }; + + for (const auto & name : testing_validators_set) { + std::cout << name << std::endl; + EXPECT_TRUE(expected_validators_set.find(name) != expected_validators_set.end()) + << "Unexpected validator found: " << name; } } @@ -154,10 +177,11 @@ TEST_F(TestSuite, MissingRegulatoryElementOfTrafficLight) // NOLINT for gtest LaneletMapPtr test_map_ptr = lanelet::utils::createMap({tl_no_reg_elem}); addTestMap(test_map_ptr); + lanelet::validation::MissingRegulatoryElementsForTrafficLightsValidator checker_; const auto & issues = checker_(*test_map_ptr); uint8_t expected_num_issues = 1; - static constexpr const char * expected_message = "Traffic light must have a regulatory element."; + static constexpr const char * expected_message = "No regulatory element refers to this traffic light."; EXPECT_EQ(expected_num_issues, issues.size()); for (const auto & issue : issues) { EXPECT_EQ(99999, issue.id); @@ -179,10 +203,11 @@ TEST_F(TestSuite, MissingRegulatoryElementOfCrosswalk) // NOLINT for gtest LaneletMapPtr test_map_ptr = lanelet::utils::createMap({cw_no_reg_elem}); addTestMap(test_map_ptr); + lanelet::validation::MissingRegulatoryElementsForCrosswalksValidator checker_; const auto & issues = checker_(*test_map_ptr); uint8_t expected_num_issues = 1; - static constexpr const char * expected_message = "Crosswalk must have a regulatory element."; + static constexpr const char * expected_message = "No regulatory element refers to this crosswalk."; EXPECT_EQ(expected_num_issues, issues.size()); for (const auto & issue : issues) { EXPECT_EQ(99999, issue.id); @@ -201,10 +226,11 @@ TEST_F(TestSuite, MissingRegulatoryElementOfStopLine) // NOLINT for gtest LaneletMapPtr test_map_ptr = lanelet::utils::createMap({sl_no_reg_elem}); addTestMap(test_map_ptr); + lanelet::validation::MissingRegulatoryElementsForStopLinesValidator checker_; const auto & issues = checker_(*test_map_ptr); uint8_t expected_num_issues = 1; - static constexpr const char * expected_message = "Stop Line must have a regulatory element."; + static constexpr const char * expected_message = "No regulatory element refers to this stop line."; EXPECT_EQ(expected_num_issues, issues.size()); for (const auto & issue : issues) { EXPECT_EQ(99999, issue.id); diff --git a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp index 41de8ded..ba953012 100644 --- a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp +++ b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp @@ -13,9 +13,8 @@ // limitations under the License. #include "autoware_lanelet2_map_validator/validators/regulatory_element_details.hpp" - -#include -#include +#include +#include #include @@ -132,7 +131,6 @@ class TestSuite : public ::testing::Test } } AttributeMap sl_attr, tl_attr, cw_attr, cw_poly_attr, tl_re_attr, cw_re_attr; - lanelet::validation::RegulatoryElementDetailsChecker checker_; private: }; @@ -140,26 +138,29 @@ class TestSuite : public ::testing::Test TEST_F(TestSuite, ValidatorAvailability) // NOLINT for gtest { std::string expected_validators_concat = - "mapping.crosswalk.missing_regulatory_elements," - "mapping.stop_line.missing_regulatory_elements," - "mapping.traffic_light.missing_regulatory_elements"; + "mapping.crosswalk.regulatory_element_details," + "mapping.traffic_light.regulatory_element_details"; lanelet::validation::Strings validators = lanelet::validation::availabeChecks( - target_validators); - uint8_t expected_num_validators = 3; + expected_validators_concat); + uint8_t expected_num_validators = 2; std::cout << "size: " << validators.size() << std::endl; EXPECT_EQ(expected_num_validators, validators.size()); std::set expected_validators_set = { - "mapping.crosswalk.missing_regulatory_elements", - "mapping.stop_line.missing_regulatory_elements", - "mapping.traffic_light.missing_regulatory_elements" + "mapping.crosswalk.regulatory_element_details", + "mapping.traffic_light.regulatory_element_details" + }; + + std::set testing_validators_set = { + lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator::name(), + lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator::name() }; - for (const auto & v : validators) { - std::cout << v.name() << std::endl; - EXPECT_TRUE(expected_validators_set.find(v.name()) != expected_validators_set.end()) - << "Unexpected validator found: " << v.name(); + for (const auto & name : testing_validators_set) { + std::cout << name << std::endl; + EXPECT_TRUE(expected_validators_set.find(name) != expected_validators_set.end()) + << "Unexpected validator found: " << name; } } @@ -180,6 +181,7 @@ TEST_F(TestSuite, RegulatoryElementofTrafficLightWithoutTrafficLight) // NOLINT test_map_ptr->add(tl_reg_elem_no_tl); addTestMap(test_map_ptr); + lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker_; const auto & issues = checker_(*test_map_ptr); uint8_t expected_num_issues = 2; @@ -219,6 +221,7 @@ TEST_F(TestSuite, RegulatoryElementofTrafficLightWithoutStopLine) // NOLINT for test_map_ptr->add(tl_reg_elem_no_sl); addTestMap(test_map_ptr); + lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker_; const auto & issues = checker_(*test_map_ptr); uint8_t expected_num_issues = 2; @@ -263,6 +266,7 @@ TEST_F(TestSuite, RegulatoryElementOfCrosswalkWithoutPolygon) // NOLINT for gte LaneletMapPtr test_map_ptr = lanelet::utils::createMap({cw_no_poly}); addTestMap(test_map_ptr); + lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker_; const auto & issues = checker_(*test_map_ptr); uint8_t expected_num_issues = 2; @@ -304,6 +308,7 @@ TEST_F(TestSuite, RegulatoryElementOfCrosswalkWithoutStopline) // NOLINT for gt LaneletMapPtr test_map_ptr = lanelet::utils::createMap({cw_no_sl}); addTestMap(test_map_ptr); + lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker_; const auto & issues = checker_(*test_map_ptr); uint8_t expected_num_issues = 1; @@ -337,6 +342,7 @@ TEST_F(TestSuite, RegulatoryElementOfCrosswalkWithoutCrosswalk) // NOLINT for g addTestMap(test_map_ptr); test_map_ptr->add(reg_elem); + lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker_; const auto & issues = checker_(*test_map_ptr); uint8_t expected_num_issues = 2; From e091ff656d63e37bec083aef38652d20e6768df0 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Thu, 19 Sep 2024 18:40:12 +0900 Subject: [PATCH 09/45] Removed unused code which are already divided to smaller codes. Signed-off-by: TaikiYamada4 --- .../missing_regulatory_elements.hpp | 54 ---- .../validators/regulatory_element_details.hpp | 50 ---- .../missing_regulatory_elements.cpp | 230 ------------------ .../validators/regulatory_element_details.cpp | 183 -------------- .../src/main.cpp | 49 ---- .../src/test_missing_regulatory_elements.cpp | 6 +- .../src/test_regulatory_element_details.cpp | 6 +- 7 files changed, 10 insertions(+), 568 deletions(-) delete mode 100644 map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/missing_regulatory_elements.hpp delete mode 100644 map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/regulatory_element_details.hpp delete mode 100644 map/autoware_lanelet2_map_validator/src/lib/validators/missing_regulatory_elements.cpp delete mode 100644 map/autoware_lanelet2_map_validator/src/lib/validators/regulatory_element_details.cpp delete mode 100644 map/autoware_lanelet2_map_validator/src/main.cpp diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/missing_regulatory_elements.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/missing_regulatory_elements.hpp deleted file mode 100644 index 71308a0a..00000000 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/missing_regulatory_elements.hpp +++ /dev/null @@ -1,54 +0,0 @@ -// Copyright 2023 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__MISSING_REGULATORY_ELEMENTS_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__MISSING_REGULATORY_ELEMENTS_HPP_ - -#include "autoware_lanelet2_map_validator/utils.hpp" - -#include -#include -#include -#include - -#include -#include - -#include - -namespace lanelet -{ -namespace validation -{ - -class MissingRegulatoryElementsChecker : public lanelet::validation::MapValidator -{ -public: - constexpr static const char * name() { return "mapping.missing_regulatory_elements"; } - - lanelet::validation::Issues operator()(const lanelet::LaneletMap & map) override; - -private: - lanelet::validation::Issues checkMissingReglatoryElementsInTrafficLight( - const lanelet::LaneletMap & map); - lanelet::validation::Issues checkMissingReglatoryElementsInCrosswalk( - const lanelet::LaneletMap & map); - lanelet::validation::Issues checkMissingReglatoryElementsInStopLine( - const lanelet::LaneletMap & map); - std::set tl_elem_with_cw_; -}; -} // namespace validation -} // namespace lanelet - -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALS__MISSING_REGULATORY_ELEMENTS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/regulatory_element_details.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/regulatory_element_details.hpp deleted file mode 100644 index 3333eae7..00000000 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/regulatory_element_details.hpp +++ /dev/null @@ -1,50 +0,0 @@ -// Copyright 2023 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware_lanelet2_map_validator/utils.hpp" - -#include -#include -#include - -#include -#include - -#include -#include - -namespace lanelet -{ -namespace validation -{ - -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__REGULATORY_ELEMENT_DETAILS_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__REGULATORY_ELEMENT_DETAILS_HPP_ - -class RegulatoryElementDetailsChecker : public lanelet::validation::MapValidator -{ -public: - constexpr static const char * name() { return "mapping.regulatory_elements_details"; } - - lanelet::validation::Issues operator()(const lanelet::LaneletMap & map) override; - -private: - bool isPedestrianTrafficLight(const std::vector & traffic_lights); - lanelet::validation::Issues checkRegulatoryElementOfTrafficLight(const lanelet::LaneletMap & map); - lanelet::validation::Issues checkRegulatoryElementOfCrosswalk(const lanelet::LaneletMap & map); -}; -} // namespace validation -} // namespace lanelet - -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALS__REGULATORY_ELEMENT_DETAILS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/missing_regulatory_elements.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/missing_regulatory_elements.cpp deleted file mode 100644 index bd23d75a..00000000 --- a/map/autoware_lanelet2_map_validator/src/lib/validators/missing_regulatory_elements.cpp +++ /dev/null @@ -1,230 +0,0 @@ -// Copyright 2023 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include - -namespace lanelet -{ -namespace validation -{ -namespace -{ -lanelet::validation::RegisterMapValidator reg; -} // namespace - -lanelet::validation::Issues MissingRegulatoryElementsChecker::operator()( - const lanelet::LaneletMap & map) -{ - // All issues found by all validators - lanelet::validation::Issues issues; - - // Append issues found by each validator - lanelet::autoware::validation::appendIssues( - issues, checkMissingReglatoryElementsInTrafficLight(map)); - lanelet::autoware::validation::appendIssues( - issues, checkMissingReglatoryElementsInCrosswalk(map)); - lanelet::autoware::validation::appendIssues(issues, checkMissingReglatoryElementsInStopLine(map)); - return issues; -} - -lanelet::validation::Issues -MissingRegulatoryElementsChecker::checkMissingReglatoryElementsInTrafficLight( - const lanelet::LaneletMap & map) -{ - lanelet::validation::Issues issues; - - // Get all line strings whose type is traffic light - auto tl_ids = - map.lineStringLayer | ranges::views::filter([](auto && ls) { - const auto & attrs = ls.attributes(); - const auto & it = attrs.find(lanelet::AttributeName::Type); - return it != attrs.end() && it->second == lanelet::AttributeValueString::TrafficLight; - }) | - ranges::views::transform([](auto && ls) { return ls.id(); }) | ranges::views::unique; - - std::cout << "tl_ids" << std::endl; - std::cout << typeid(decltype(tl_ids)).name() << std::endl; - for (const auto & id : tl_ids) { - std::cout << id << std::endl; - } - - // Filter regulatory elements whose type is traffic light and has refers - auto reg_elem_tl = map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { - const auto & attrs = elem->attributes(); - const auto & it = attrs.find(lanelet::AttributeName::Subtype); - const auto & params = elem->getParameters(); - return it != attrs.end() && - it->second == lanelet::AttributeValueString::TrafficLight && - params.find(lanelet::RoleNameString::Refers) != params.end(); - }); - std::cout << "reg_elem_tl" << std::endl; - for (const auto & id : reg_elem_tl) { - std::cout << id << std::endl; - } - - // Get all line strings of traffic light referred by regulatory elements - std::set tl_ids_reg_elem; - for (const auto & elem : reg_elem_tl) { - const auto & refers = - elem->getParameters(lanelet::RoleName::Refers); - for (const auto & refer : refers) { - tl_ids_reg_elem.insert(refer.id()); - } - } - - std::cout << "tl_ids_reg_elem" << std::endl; - for (const auto & id : tl_ids_reg_elem) { - std::cout << id << std::endl; - } - - // Check if all line strings of traffic light referred by regulatory elements - for (const auto & tl_id : tl_ids) { - if (tl_ids_reg_elem.find(tl_id) == tl_ids_reg_elem.end()) { - issues.emplace_back( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, tl_id, - "Traffic light must have a regulatory element."); - } - } - - return issues; -} - -lanelet::validation::Issues -MissingRegulatoryElementsChecker::checkMissingReglatoryElementsInCrosswalk( - const lanelet::LaneletMap & map) -{ - lanelet::validation::Issues issues; - - // Get all lanelets whose type is crosswalk - std::set cw_ids; - for (const auto & ll : map.laneletLayer) { - const auto & attrs = ll.attributes(); - const auto & it = attrs.find(lanelet::AttributeName::Subtype); - // Check if this lanelet is crosswalk - if (it != attrs.end() && it->second == lanelet::AttributeValueString::Crosswalk) { - cw_ids.insert(ll.id()); - - // Check if crosswalk has reg elem of traffic light - for (const auto & elem : ll.regulatoryElements()) { - const auto & attrs = elem->attributes(); - const auto & it = attrs.find(lanelet::AttributeName::Subtype); - if (it != attrs.end() && it->second == lanelet::AttributeValueString::TrafficLight) { - tl_elem_with_cw_.insert(elem->id()); - } - } - } - } - - std::cout << "cw_ids" << std::endl; - for (const auto & id : cw_ids) { - std::cout << id << std::endl; - } - - std::cout << "tl_elem_with_cw_" << std::endl; - for (const auto & id : tl_elem_with_cw_) { - std::cout << id << std::endl; - } - - // Filter regulatory elements whose type is crosswalk and has refers - auto reg_elem_cw = - map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { - const auto & attrs = elem->attributes(); - const auto & it = attrs.find(lanelet::AttributeName::Subtype); - return it != attrs.end() && it->second == lanelet::AttributeValueString::Crosswalk; - }) | - ranges::views::filter([](auto && elem) { - const auto & param = elem->getParameters(); - return param.find(lanelet::RoleNameString::Refers) != param.end(); - }); - - std::cout << "reg_elem_cw" << std::endl; - for (const auto & id : reg_elem_cw) { - std::cout << id << std::endl; - } - - // Get all lanelets of crosswalk referred by regulatory elements - std::set cw_ids_reg_elem; - for (const auto & elem : reg_elem_cw) { - const auto & refers = elem->getParameters(lanelet::RoleName::Refers); - for (const lanelet::ConstLanelet & refer : refers) { - cw_ids_reg_elem.insert(refer.id()); - } - } - - std::cout << "cw_ids_reg_elem" << std::endl; - for (const auto & id : cw_ids_reg_elem) { - std::cout << id << std::endl; - } - - // Check if all lanelets of crosswalk referred by regulatory elements - for (const auto & cw_id : cw_ids) { - if (cw_ids_reg_elem.find(cw_id) == cw_ids_reg_elem.end()) { - issues.emplace_back( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::Lanelet, cw_id, - "Crosswalk must have a regulatory element."); - } - } - - return issues; -} - -lanelet::validation::Issues -MissingRegulatoryElementsChecker::checkMissingReglatoryElementsInStopLine( - const lanelet::LaneletMap & map) -{ - lanelet::validation::Issues issues; - - // Get all line strings whose type is stop line - auto sl_ids = map.lineStringLayer | ranges::views::filter([](auto && ls) { - const auto & attrs = ls.attributes(); - const auto & it = attrs.find(lanelet::AttributeName::Type); - return it != attrs.end() && it->second == lanelet::AttributeValueString::StopLine; - }) | - ranges::views::transform([](auto && ls) { return ls.id(); }) | - ranges::views::unique; - - // Filter regulatory elements whose refline type is stop line - auto reg_elem_sl = map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { - const auto & params = elem->getParameters(); - return params.find(lanelet::RoleNameString::RefLine) != params.end(); - }); - - // Get all line strings of stop line referred by regulatory elements - std::set sl_ids_reg_elem; - for (const auto & elem : reg_elem_sl) { - const auto & ref_lines = - elem->getParameters(lanelet::RoleName::RefLine); - for (const auto & ref_line : ref_lines) { - const auto & attrs = ref_line.attributes(); - const auto & it = attrs.find(lanelet::AttributeName::Type); - if (it != attrs.end() && it->second == lanelet::AttributeValueString::StopLine) { - sl_ids_reg_elem.insert(ref_line.id()); - } - } - } - - // Check if all line strings of stop line referred by regulatory elements - for (const auto & sl_id : sl_ids) { - if (sl_ids_reg_elem.find(sl_id) == sl_ids_reg_elem.end()) { - issues.emplace_back( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, sl_id, - "Stop Line must have a regulatory element."); - } - } - - return issues; -} - -} // namespace validation -} // namespace lanelet diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/regulatory_element_details.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/regulatory_element_details.cpp deleted file mode 100644 index 75883768..00000000 --- a/map/autoware_lanelet2_map_validator/src/lib/validators/regulatory_element_details.cpp +++ /dev/null @@ -1,183 +0,0 @@ -// Copyright 2023 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware_lanelet2_map_validator/validators/regulatory_element_details.hpp" - -namespace lanelet -{ -namespace validation -{ -namespace -{ -lanelet::validation::RegisterMapValidator reg; -} // namespace - -lanelet::validation::Issues RegulatoryElementDetailsChecker::operator()( - const lanelet::LaneletMap & map) -{ - // All issues found by all validators - lanelet::validation::Issues issues; - - // Append issues found by each validator - lanelet::autoware::validation::appendIssues(issues, checkRegulatoryElementOfTrafficLight(map)); - lanelet::autoware::validation::appendIssues(issues, checkRegulatoryElementOfCrosswalk(map)); - return issues; -} - -bool RegulatoryElementDetailsChecker::isPedestrianTrafficLight( - const std::vector & traffic_lights) -{ - for (const auto & tl : traffic_lights) { - const auto & attrs = tl.attributes(); - const auto & it = attrs.find(lanelet::AttributeName::Subtype); - if (it == attrs.end() || it->second != "red_green") { - return false; - } - } - return true; -} - -lanelet::validation::Issues RegulatoryElementDetailsChecker::checkRegulatoryElementOfTrafficLight( - const lanelet::LaneletMap & map) -{ - lanelet::validation::Issues issues; - // filter regulatory element whose Subtype is traffic light - auto elems = - map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { - const auto & attrs = elem->attributes(); - const auto & it = attrs.find(lanelet::AttributeName::Subtype); - return it != attrs.end() && it->second == lanelet::AttributeValueString::TrafficLight; - }); - - for (const auto & elem : elems) { - // Get line strings of traffic light referred by regulatory element - auto refers = elem->getParameters(lanelet::RoleName::Refers); - // Get stop line referred by regulatory element - auto ref_lines = elem->getParameters(lanelet::RoleName::RefLine); - const auto & issue_tl = lanelet::validation::Issue( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, - lanelet::utils::getId(), - "Refers of traffic light regulatory element must have type of traffic_light."); - lanelet::autoware::validation::checkPrimitivesType( - refers, lanelet::AttributeValueString::TrafficLight, issue_tl, issues); - - const auto & issue_sl = lanelet::validation::Issue( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, - lanelet::utils::getId(), - "Refline of traffic light regulatory element must have type of stop_line."); - lanelet::autoware::validation::checkPrimitivesType( - ref_lines, lanelet::AttributeValueString::StopLine, issue_sl, issues); - - if (refers.empty()) { - issues.emplace_back( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, - elem->id(), "Regulatory element of traffic light must have a traffic light(refers)."); - } - // TODO(sgk-000): Check correct behavior if regulatory element has two or more traffic light - // else if (refers.size() != 1) { - // issues.emplace_back( - // lanelet::validation::Severity::Error, - // lanelet::validation::Primitive::RegulatoryElement, elem->id(), "Regulatory element of - // traffic light must have only one traffic light(refers)."); - // } - - // Report error if regulatory element does not have stop line and this is not a pedestrian - // traffic light - if (ref_lines.empty() && !isPedestrianTrafficLight(refers)) { - issues.emplace_back( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, - elem->id(), "Regulatory element of traffic light must have a stop line(ref_line)."); - } - } - return issues; -} - -lanelet::validation::Issues RegulatoryElementDetailsChecker::checkRegulatoryElementOfCrosswalk( - const lanelet::LaneletMap & map) -{ - lanelet::validation::Issues issues; - // filter elem whose Subtype is crosswalk - auto elems = map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { - const auto & attrs = elem->attributes(); - const auto & it = attrs.find(lanelet::AttributeName::Subtype); - return it != attrs.end() && it->second == lanelet::AttributeValueString::Crosswalk; - }); - - for (const auto & elem : elems) { - // Get lanelet of crosswalk referred by regulatory element - auto refers = elem->getParameters(lanelet::RoleName::Refers); - // Get stop line referred by regulatory element - auto ref_lines = elem->getParameters(lanelet::RoleName::RefLine); - // Get crosswalk polygon referred by regulatory element - auto crosswalk_polygons = elem->getParameters( - lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon); - - const auto & issue_cw = lanelet::validation::Issue( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::Lanelet, - lanelet::utils::getId(), - "Refers of crosswalk regulatory element must have type of crosswalk."); - lanelet::autoware::validation::checkPrimitivesType( - refers, lanelet::AttributeValueString::Lanelet, lanelet::AttributeValueString::Crosswalk, - issue_cw, issues); - - const auto & issue_sl = lanelet::validation::Issue( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, - lanelet::utils::getId(), - "Refline of crosswalk regulatory element must have type of stopline."); - lanelet::autoware::validation::checkPrimitivesType( - ref_lines, lanelet::AttributeValueString::StopLine, issue_sl, issues); - - const auto & issue_poly = lanelet::validation::Issue( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::Polygon, - lanelet::utils::getId(), - "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon."); - lanelet::autoware::validation::checkPrimitivesType( - crosswalk_polygons, lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon, - issue_poly, issues); - - // Report warning if regulatory element does not have crosswalk polygon - if (crosswalk_polygons.empty()) { - issues.emplace_back( - lanelet::validation::Severity::Warning, lanelet::validation::Primitive::RegulatoryElement, - elem->id(), "Regulatory element of cross walk is nice to have crosswalk_polygon."); - } else if (crosswalk_polygons.size() > 1) { // Report error if regulatory element has two or - // more crosswalk polygon - issues.emplace_back( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, - elem->id(), "Regulatory element of cross walk must have only one crosswalk_polygon."); - } - // Report Info if regulatory element does not have stop line - if (ref_lines.empty()) { - issues.emplace_back( - lanelet::validation::Severity::Info, lanelet::validation::Primitive::RegulatoryElement, - elem->id(), "Regulatory element of cross walk does not have stop line(ref_line)."); - } - // Report error if regulatory element does not have lanelet of crosswalk - if (refers.empty()) { - issues.emplace_back( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, - elem->id(), "Regulatory element of cross walk must have lanelet of crosswalk(refers)."); - } else if (refers.size() > 1) { // Report error if regulatory element has two or more lanelet - // of crosswalk - issues.emplace_back( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, - elem->id(), - "Regulatory element of cross walk must have only one lanelet of crosswalk(refers)."); - } - } - return issues; -} - -} // namespace validation -} // namespace lanelet diff --git a/map/autoware_lanelet2_map_validator/src/main.cpp b/map/autoware_lanelet2_map_validator/src/main.cpp deleted file mode 100644 index b3d579b7..00000000 --- a/map/autoware_lanelet2_map_validator/src/main.cpp +++ /dev/null @@ -1,49 +0,0 @@ -// Copyright 2023 Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "autoware_lanelet2_map_validator/validation.hpp" -#include "lanelet2_validation/Validation.h" - -int main(int argc, char * argv[]) -{ - auto config = lanelet::autoware::validation::parseCommandLine( - argc, const_cast(argv)); // NOLINT - - auto command_line_config = config.command_line_config; - if (command_line_config.help) { - return 0; - } - if (command_line_config.print) { - auto checks = - lanelet::validation::availabeChecks(command_line_config.validationConfig.checksFilter); - if (checks.empty()) { - std::cout << "No checks found matching '" << command_line_config.validationConfig.checksFilter - << "'\n"; - } else { - std::cout << "Will use following checks:\n"; - for (auto & check : checks) { - std::cout << check << '\n'; - } - } - return 0; - } - if (command_line_config.mapFile.empty()) { - std::cout << "No map file specified" << std::endl; - return 1; - } - - auto issues = lanelet::autoware::validation::validateMap(config); - lanelet::validation::printAllIssues(issues); - return static_cast(!issues.empty()); -} diff --git a/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp index 52da8ed9..b03a8851 100644 --- a/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp +++ b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp @@ -12,11 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_lanelet2_map_validator/validators/missing_regulatory_elements.hpp" #include #include #include +#include +#include + +#include + #include using lanelet::AttributeMap; diff --git a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp index ba953012..4d43d833 100644 --- a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp +++ b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp @@ -12,10 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_lanelet2_map_validator/validators/regulatory_element_details.hpp" #include #include +#include +#include + +#include + #include using lanelet::AttributeMap; From 359f3595597e02f9cedc3456add641709eea1463 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Thu, 19 Sep 2024 18:48:20 +0900 Subject: [PATCH 10/45] Rename new_main.cpp to main.cpp Signed-off-by: TaikiYamada4 --- map/autoware_lanelet2_map_validator/CMakeLists.txt | 2 +- .../src/{new_main.cpp => main.cpp} | 0 2 files changed, 1 insertion(+), 1 deletion(-) rename map/autoware_lanelet2_map_validator/src/{new_main.cpp => main.cpp} (100%) diff --git a/map/autoware_lanelet2_map_validator/CMakeLists.txt b/map/autoware_lanelet2_map_validator/CMakeLists.txt index a4d86f2c..2f0c57ab 100644 --- a/map/autoware_lanelet2_map_validator/CMakeLists.txt +++ b/map/autoware_lanelet2_map_validator/CMakeLists.txt @@ -16,7 +16,7 @@ ament_auto_add_library(autoware_lanelet2_map_validator_lib SHARED ${autoware_lanelet2_map_validator_lib_src} ) -ament_auto_add_executable(autoware_lanelet2_map_validator src/new_main.cpp) +ament_auto_add_executable(autoware_lanelet2_map_validator src/main.cpp) add_dependencies(autoware_lanelet2_map_validator autoware_lanelet2_map_validator_lib) target_link_libraries(autoware_lanelet2_map_validator autoware_lanelet2_map_validator_lib diff --git a/map/autoware_lanelet2_map_validator/src/new_main.cpp b/map/autoware_lanelet2_map_validator/src/main.cpp similarity index 100% rename from map/autoware_lanelet2_map_validator/src/new_main.cpp rename to map/autoware_lanelet2_map_validator/src/main.cpp From e622c910ee7ef0664777b8c2ba8ca89f1743902e Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 20 Sep 2024 02:09:58 +0000 Subject: [PATCH 11/45] style(pre-commit): autofix --- ...ing_regulatory_elements_for_crosswalks.hpp | 12 +- ...ulatory_element_details_for_crosswalks.hpp | 10 +- ...ing_regulatory_elements_for_stop_lines.hpp | 7 +- ...regulatory_elements_for_traffic_lights.hpp | 12 +- ...ory_element_details_for_traffic_lights.hpp | 18 +- .../validators/validator_template.hpp | 6 +- .../package.xml | 4 +- .../src/lib/cli.cpp | 58 +++---- .../src/lib/validation.cpp | 2 +- ...sing_regulatory_elements_for_crosswalk.cpp | 125 +++++++------- ...ulatory_element_details_for_crosswalks.cpp | 158 +++++++++--------- ...ing_regulatory_elements_for_stop_lines.cpp | 105 ++++++------ ..._regulatory_elements_for_traffic_light.cpp | 107 ++++++------ ...ory_element_details_for_traffic_lights.cpp | 136 +++++++-------- .../src/lib/validators/validator_template.cpp | 23 ++- .../src/main.cpp | 85 ++++++---- .../src/test_missing_regulatory_elements.cpp | 27 ++- .../src/test_regulatory_element_details.cpp | 18 +- 18 files changed, 459 insertions(+), 454 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp index 26e4006b..7f4db1ae 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ #include #include @@ -25,7 +25,6 @@ namespace validation class MissingRegulatoryElementsForCrosswalksValidator : public lanelet::validation::MapValidator { public: - constexpr static const char * name() { return "mapping.crosswalk.missing_regulatory_elements"; } lanelet::validation::Issues operator()(const lanelet::LaneletMap & map) override; @@ -33,9 +32,8 @@ class MissingRegulatoryElementsForCrosswalksValidator : public lanelet::validati private: lanelet::validation::Issues checkMissingRegulatoryElementsForCrosswalks( const lanelet::LaneletMap & map); - }; -} // namespace validation -} // namespace lanelet +} // namespace validation +} // namespace lanelet -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ \ No newline at end of file +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp index d2965715..1b4f9265 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALK_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALK_HPP_ +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ #include #include @@ -33,7 +33,7 @@ class RegulatoryElementsDetailsForCrosswalksValidator : public lanelet::validati private: lanelet::validation::Issues checkRegulatoryElementOfCrosswalks(const lanelet::LaneletMap & map); }; -} // namespace validation -} // namespace lanelet +} // namespace validation +} // namespace lanelet -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALK_HPP_ \ No newline at end of file +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp index 70560b76..c99add9a 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp @@ -25,7 +25,6 @@ namespace validation class MissingRegulatoryElementsForStopLinesValidator : public lanelet::validation::MapValidator { public: - constexpr static const char * name() { return "mapping.stop_line.missing_regulatory_elements"; } lanelet::validation::Issues operator()(const lanelet::LaneletMap & map) override; @@ -34,7 +33,7 @@ class MissingRegulatoryElementsForStopLinesValidator : public lanelet::validatio lanelet::validation::Issues checkMissingRegulatoryElementsForStopLines( const lanelet::LaneletMap & map); }; -} // namespace validation -} // namespace lanelet +} // namespace validation +} // namespace lanelet -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ \ No newline at end of file +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp index 72d96af4..e854ef23 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp @@ -25,8 +25,10 @@ namespace validation class MissingRegulatoryElementsForTrafficLightsValidator : public lanelet::validation::MapValidator { public: - - constexpr static const char * name() { return "mapping.traffic_light.missing_regulatory_elements"; } + constexpr static const char * name() + { + return "mapping.traffic_light.missing_regulatory_elements"; + } lanelet::validation::Issues operator()(const lanelet::LaneletMap & map) override; @@ -34,7 +36,7 @@ class MissingRegulatoryElementsForTrafficLightsValidator : public lanelet::valid lanelet::validation::Issues checkMissingRegulatoryElementsForTrafficLights( const lanelet::LaneletMap & map); }; -} // namespace validation -} // namespace lanelet +} // namespace validation +} // namespace lanelet -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ \ No newline at end of file +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp index 5b50624f..d0411fe1 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHTS__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHTS__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ #include #include @@ -28,15 +28,19 @@ class RegulatoryElementsDetailsForTrafficLightsValidator : public lanelet::valid { public: // Write the validator's name here - constexpr static const char * name() { return "mapping.traffic_light.regulatory_element_details"; } + constexpr static const char * name() + { + return "mapping.traffic_light.regulatory_element_details"; + } lanelet::validation::Issues operator()(const lanelet::LaneletMap & map) override; private: bool isPedestrianTrafficLight(const std::vector & traffic_lights); - lanelet::validation::Issues checkRegulatoryElementOfTrafficLights(const lanelet::LaneletMap & map); + lanelet::validation::Issues checkRegulatoryElementOfTrafficLights( + const lanelet::LaneletMap & map); }; -} // namespace validation -} // namespace lanelet +} // namespace validation +} // namespace lanelet -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHTS__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ \ No newline at end of file +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/validator_template.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/validator_template.hpp index 20a71100..b9dbb2df 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/validator_template.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/validator_template.hpp @@ -32,7 +32,7 @@ class ValidatorTemplate : public lanelet::validation::MapValidator private: }; -} // namespace validation -} // namespace lanelet +} // namespace validation +} // namespace lanelet -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__VALIDATOR_TEMPLATE_HPP_ \ No newline at end of file +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__VALIDATOR_TEMPLATE_HPP_ diff --git a/map/autoware_lanelet2_map_validator/package.xml b/map/autoware_lanelet2_map_validator/package.xml index 6930eb3d..ac0d12eb 100644 --- a/map/autoware_lanelet2_map_validator/package.xml +++ b/map/autoware_lanelet2_map_validator/package.xml @@ -10,8 +10,6 @@ ament_cmake_auto autoware_cmake - yaml-cpp - autoware_lanelet2_extension lanelet2_core lanelet2_io @@ -20,6 +18,8 @@ lanelet2_routing lanelet2_traffic_rules lanelet2_validation + yaml-cpp + ament_cmake_ros diff --git a/map/autoware_lanelet2_map_validator/src/lib/cli.cpp b/map/autoware_lanelet2_map_validator/src/lib/cli.cpp index 80da4ec9..0aef833b 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/cli.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/cli.cpp @@ -34,42 +34,44 @@ MetaConfig parseCommandLine(int argc, const char * argv[]) ("map_file,m", po::value(), "Path to the map to be validated") - ("requirements_file,r", po::value(), - "Path to the yaml file where the list of requirements and validations is written") + ("requirements_file,r", po::value(), + "Path to the yaml file where the list of requirements and validations is written") - ("output_file_path,o", po::value(), - "Path of the yaml file where the list of validation results will be written") + ("output_file_path,o", po::value(), + "Path of the yaml file where the list of validation results will be written") - ("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") + ("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") - ("projector,p", po::value(&config.projector_type)->composing(), - "Projector used for loading lanelet map. Available projectors are: mgrs, utm, " - "transverse_mercator. (default: mgrs)") + ("projector,p", po::value(&config.projector_type)->composing(), + "Projector used for loading lanelet map. Available projectors are: mgrs, utm, " + "transverse_mercator. (default: mgrs)") - ("location,l", - po::value(&validation_config.location)->default_value(validation_config.location), - "Location of the map (for instanciating the traffic rules), e.g. de for Germany") + ("location,l", + po::value(&validation_config.location)->default_value(validation_config.location), + "Location of the map (for instanciating the traffic rules), e.g. de for Germany") - ("participants", po::value(&validation_config.participants)->composing(), - "Participants for which the routing graph will be instanciated (default: vehicle)") + ("participants", po::value(&validation_config.participants)->composing(), + "Participants for which the routing graph will be instanciated (default: vehicle)") - ("lat", - po::value(&validation_config.origin.lat) - ->default_value(validation_config.origin.lat), - "latitude coordinate of map origin. This is reguired for the transverse mercator " - "and utm projector.") + ("lat", + po::value(&validation_config.origin.lat) + ->default_value(validation_config.origin.lat), + "latitude coordinate of map origin. This is reguired for the transverse " + "mercator " + "and utm projector.") - ("lon", - po::value(&validation_config.origin.lon) - ->default_value(validation_config.origin.lon), - "longitude coofdinate of map origin. This is reguired for the transverse mercator " - "and utm projector.") + ("lon", + po::value(&validation_config.origin.lon) + ->default_value(validation_config.origin.lon), + "longitude coofdinate of map origin. This is reguired for the transverse " + "mercator " + "and utm projector.") - ("print", "Only print all avalible checker, but dont run them"); + ("print", "Only print all avalible checker, but dont run them"); po::variables_map vm; po::positional_options_description pos; pos.add("map_file", 1); diff --git a/map/autoware_lanelet2_map_validator/src/lib/validation.cpp b/map/autoware_lanelet2_map_validator/src/lib/validation.cpp index e12a86be..3155f103 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validation.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/validation.cpp @@ -35,7 +35,7 @@ std::unique_ptr getProjector(const MetaConfig & config) } else if (config.projector_type == projector_names::utm) { return std::make_unique(lanelet::Origin{val_config.origin}); } else { - //std::cerr << "Set to default projector: MGRS projector" << std::endl; + // std::cerr << "Set to default projector: MGRS projector" << std::endl; return std::make_unique(); } } diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp index 714e153a..ec2e78a2 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp @@ -14,7 +14,6 @@ #include #include - #include #include @@ -25,80 +24,80 @@ namespace lanelet { namespace validation { -namespace +namespace { - lanelet::validation::RegisterMapValidator reg; +lanelet::validation::RegisterMapValidator reg; } - lanelet::validation::Issues MissingRegulatoryElementsForCrosswalksValidator::operator()( - const lanelet::LaneletMap & map) - { - lanelet::validation::Issues issues; - - lanelet::autoware::validation::appendIssues( - issues, checkMissingRegulatoryElementsForCrosswalks(map)); - - return issues; - } +lanelet::validation::Issues MissingRegulatoryElementsForCrosswalksValidator::operator()( + const lanelet::LaneletMap & map) +{ + lanelet::validation::Issues issues; - lanelet::validation::Issues - MissingRegulatoryElementsForCrosswalksValidator::checkMissingRegulatoryElementsForCrosswalks( - const lanelet::LaneletMap & map) - { - lanelet::validation::Issues issues; + lanelet::autoware::validation::appendIssues( + issues, checkMissingRegulatoryElementsForCrosswalks(map)); - // Get all lanelets whose type is crosswalk - std::set cw_ids; - std::set tl_elem_with_cw_; - for (const auto & ll : map.laneletLayer) { - const auto & attrs = ll.attributes(); - const auto & it = attrs.find(lanelet::AttributeName::Subtype); - // Check if this lanelet is crosswalk - if (it != attrs.end() && it->second == lanelet::AttributeValueString::Crosswalk) { - cw_ids.insert(ll.id()); + return issues; +} - // Check if crosswalk has reg elem of traffic light - for (const auto & elem : ll.regulatoryElements()) { - const auto & attrs = elem->attributes(); - const auto & it = attrs.find(lanelet::AttributeName::Subtype); - if (it != attrs.end() && it->second == lanelet::AttributeValueString::TrafficLight) { - tl_elem_with_cw_.insert(elem->id()); - } - } - } - } +lanelet::validation::Issues +MissingRegulatoryElementsForCrosswalksValidator::checkMissingRegulatoryElementsForCrosswalks( + const lanelet::LaneletMap & map) +{ + lanelet::validation::Issues issues; + + // Get all lanelets whose type is crosswalk + std::set cw_ids; + std::set tl_elem_with_cw_; + for (const auto & ll : map.laneletLayer) { + const auto & attrs = ll.attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + // Check if this lanelet is crosswalk + if (it != attrs.end() && it->second == lanelet::AttributeValueString::Crosswalk) { + cw_ids.insert(ll.id()); - // Filter regulatory elements whose type is crosswalk and has refers - auto reg_elem_cw = - map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { + // Check if crosswalk has reg elem of traffic light + for (const auto & elem : ll.regulatoryElements()) { const auto & attrs = elem->attributes(); const auto & it = attrs.find(lanelet::AttributeName::Subtype); - return it != attrs.end() && it->second == lanelet::AttributeValueString::Crosswalk; - }) | - ranges::views::filter([](auto && elem) { - const auto & param = elem->getParameters(); - return param.find(lanelet::RoleNameString::Refers) != param.end(); - }); - - // Get all lanelets of crosswalk referred by regulatory elements - std::set cw_ids_reg_elem; - for (const auto & elem : reg_elem_cw) { - const auto & refers = elem->getParameters(lanelet::RoleName::Refers); - for (const lanelet::ConstLanelet & refer : refers) { - cw_ids_reg_elem.insert(refer.id()); + if (it != attrs.end() && it->second == lanelet::AttributeValueString::TrafficLight) { + tl_elem_with_cw_.insert(elem->id()); + } } } + } - // Check if all lanelets of crosswalk referred by regulatory elements - for (const auto & cw_id : cw_ids) { - if (cw_ids_reg_elem.find(cw_id) == cw_ids_reg_elem.end()) { - issues.emplace_back( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::Lanelet, cw_id, - "No regulatory element refers to this crosswalk."); - } + // Filter regulatory elements whose type is crosswalk and has refers + auto reg_elem_cw = + map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { + const auto & attrs = elem->attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + return it != attrs.end() && it->second == lanelet::AttributeValueString::Crosswalk; + }) | + ranges::views::filter([](auto && elem) { + const auto & param = elem->getParameters(); + return param.find(lanelet::RoleNameString::Refers) != param.end(); + }); + + // Get all lanelets of crosswalk referred by regulatory elements + std::set cw_ids_reg_elem; + for (const auto & elem : reg_elem_cw) { + const auto & refers = elem->getParameters(lanelet::RoleName::Refers); + for (const lanelet::ConstLanelet & refer : refers) { + cw_ids_reg_elem.insert(refer.id()); } + } - return issues; + // Check if all lanelets of crosswalk referred by regulatory elements + for (const auto & cw_id : cw_ids) { + if (cw_ids_reg_elem.find(cw_id) == cw_ids_reg_elem.end()) { + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::Lanelet, cw_id, + "No regulatory element refers to this crosswalk."); + } } -} // namespace validation -} // namespace lanelet2 \ No newline at end of file + + return issues; +} +} // namespace validation +} // namespace lanelet diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp index 05f56a80..b04a0eb0 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp @@ -12,12 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. - #include - #include #include - #include #include @@ -32,92 +29,93 @@ namespace lanelet::validation::RegisterMapValidator reg; } // namespace - lanelet::validation::Issues RegulatoryElementsDetailsForCrosswalksValidator::operator()( - const lanelet::LaneletMap & map) - { - // All issues found by all validators - lanelet::validation::Issues issues; +lanelet::validation::Issues RegulatoryElementsDetailsForCrosswalksValidator::operator()( + const lanelet::LaneletMap & map) +{ + // All issues found by all validators + lanelet::validation::Issues issues; - // Append issues found by each validator - lanelet::autoware::validation::appendIssues(issues, checkRegulatoryElementOfCrosswalks(map)); - return issues; - } + // Append issues found by each validator + lanelet::autoware::validation::appendIssues(issues, checkRegulatoryElementOfCrosswalks(map)); + return issues; +} - lanelet::validation::Issues RegulatoryElementsDetailsForCrosswalksValidator::checkRegulatoryElementOfCrosswalks( - const lanelet::LaneletMap & map) - { - lanelet::validation::Issues issues; - // filter elem whose Subtype is crosswalk - auto elems = map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { - const auto & attrs = elem->attributes(); - const auto & it = attrs.find(lanelet::AttributeName::Subtype); - return it != attrs.end() && it->second == lanelet::AttributeValueString::Crosswalk; - }); +lanelet::validation::Issues +RegulatoryElementsDetailsForCrosswalksValidator::checkRegulatoryElementOfCrosswalks( + const lanelet::LaneletMap & map) +{ + lanelet::validation::Issues issues; + // filter elem whose Subtype is crosswalk + auto elems = map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { + const auto & attrs = elem->attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + return it != attrs.end() && it->second == lanelet::AttributeValueString::Crosswalk; + }); - for (const auto & elem : elems) { - // Get lanelet of crosswalk referred by regulatory element - auto refers = elem->getParameters(lanelet::RoleName::Refers); - // Get stop line referred by regulatory element - auto ref_lines = elem->getParameters(lanelet::RoleName::RefLine); - // Get crosswalk polygon referred by regulatory element - auto crosswalk_polygons = elem->getParameters( - lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon); + for (const auto & elem : elems) { + // Get lanelet of crosswalk referred by regulatory element + auto refers = elem->getParameters(lanelet::RoleName::Refers); + // Get stop line referred by regulatory element + auto ref_lines = elem->getParameters(lanelet::RoleName::RefLine); + // Get crosswalk polygon referred by regulatory element + auto crosswalk_polygons = elem->getParameters( + lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon); - const auto & issue_cw = lanelet::validation::Issue( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::Lanelet, - lanelet::utils::getId(), - "Refers of crosswalk regulatory element must have type of crosswalk."); - lanelet::autoware::validation::checkPrimitivesType( - refers, lanelet::AttributeValueString::Lanelet, lanelet::AttributeValueString::Crosswalk, - issue_cw, issues); + const auto & issue_cw = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::Lanelet, + lanelet::utils::getId(), + "Refers of crosswalk regulatory element must have type of crosswalk."); + lanelet::autoware::validation::checkPrimitivesType( + refers, lanelet::AttributeValueString::Lanelet, lanelet::AttributeValueString::Crosswalk, + issue_cw, issues); - const auto & issue_sl = lanelet::validation::Issue( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, - lanelet::utils::getId(), - "Refline of crosswalk regulatory element must have type of stopline."); - lanelet::autoware::validation::checkPrimitivesType( - ref_lines, lanelet::AttributeValueString::StopLine, issue_sl, issues); + const auto & issue_sl = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, + lanelet::utils::getId(), + "Refline of crosswalk regulatory element must have type of stopline."); + lanelet::autoware::validation::checkPrimitivesType( + ref_lines, lanelet::AttributeValueString::StopLine, issue_sl, issues); - const auto & issue_poly = lanelet::validation::Issue( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::Polygon, - lanelet::utils::getId(), - "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon."); - lanelet::autoware::validation::checkPrimitivesType( - crosswalk_polygons, lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon, - issue_poly, issues); + const auto & issue_poly = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::Polygon, + lanelet::utils::getId(), + "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon."); + lanelet::autoware::validation::checkPrimitivesType( + crosswalk_polygons, lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon, + issue_poly, issues); - // Report warning if regulatory element does not have crosswalk polygon - if (crosswalk_polygons.empty()) { - issues.emplace_back( - lanelet::validation::Severity::Warning, lanelet::validation::Primitive::RegulatoryElement, - elem->id(), "Regulatory element of cross walk is nice to have crosswalk_polygon."); - } else if (crosswalk_polygons.size() > 1) { // Report error if regulatory element has two or - // more crosswalk polygon - issues.emplace_back( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, - elem->id(), "Regulatory element of cross walk must have only one crosswalk_polygon."); - } - // Report Info if regulatory element does not have stop line - if (ref_lines.empty()) { - issues.emplace_back( - lanelet::validation::Severity::Info, lanelet::validation::Primitive::RegulatoryElement, - elem->id(), "Regulatory element of cross walk does not have stop line(ref_line)."); - } - // Report error if regulatory element does not have lanelet of crosswalk - if (refers.empty()) { - issues.emplace_back( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, - elem->id(), "Regulatory element of cross walk must have lanelet of crosswalk(refers)."); - } else if (refers.size() > 1) { // Report error if regulatory element has two or more lanelet - // of crosswalk - issues.emplace_back( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, - elem->id(), - "Regulatory element of cross walk must have only one lanelet of crosswalk(refers)."); - } + // Report warning if regulatory element does not have crosswalk polygon + if (crosswalk_polygons.empty()) { + issues.emplace_back( + lanelet::validation::Severity::Warning, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), "Regulatory element of cross walk is nice to have crosswalk_polygon."); + } else if (crosswalk_polygons.size() > 1) { // Report error if regulatory element has two or + // more crosswalk polygon + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), "Regulatory element of cross walk must have only one crosswalk_polygon."); + } + // Report Info if regulatory element does not have stop line + if (ref_lines.empty()) { + issues.emplace_back( + lanelet::validation::Severity::Info, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), "Regulatory element of cross walk does not have stop line(ref_line)."); + } + // Report error if regulatory element does not have lanelet of crosswalk + if (refers.empty()) { + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), "Regulatory element of cross walk must have lanelet of crosswalk(refers)."); + } else if (refers.size() > 1) { // Report error if regulatory element has two or more lanelet + // of crosswalk + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), + "Regulatory element of cross walk must have only one lanelet of crosswalk(refers)."); } - return issues; } + return issues; +} } // namespace validation } // namespace lanelet diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp index 1b6a9da0..4c1c6958 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp @@ -14,7 +14,6 @@ #include #include - #include #include #include @@ -27,68 +26,68 @@ namespace lanelet { namespace validation { -namespace +namespace { - lanelet::validation::RegisterMapValidator reg; +lanelet::validation::RegisterMapValidator reg; } - lanelet::validation::Issues MissingRegulatoryElementsForStopLinesValidator::operator()( - const lanelet::LaneletMap & map) - { - lanelet::validation::Issues issues; - - lanelet::autoware::validation::appendIssues( - issues, checkMissingRegulatoryElementsForStopLines(map)); - - return issues; - } +lanelet::validation::Issues MissingRegulatoryElementsForStopLinesValidator::operator()( + const lanelet::LaneletMap & map) +{ + lanelet::validation::Issues issues; - lanelet::validation::Issues - MissingRegulatoryElementsForStopLinesValidator::checkMissingRegulatoryElementsForStopLines( - const lanelet::LaneletMap & map) - { - lanelet::validation::Issues issues; + lanelet::autoware::validation::appendIssues( + issues, checkMissingRegulatoryElementsForStopLines(map)); - // Get all line strings whose type is stop line - auto sl_ids = map.lineStringLayer | ranges::views::filter([](auto && ls) { - const auto & attrs = ls.attributes(); - const auto & it = attrs.find(lanelet::AttributeName::Type); - return it != attrs.end() && it->second == lanelet::AttributeValueString::StopLine; - }) | - ranges::views::transform([](auto && ls) { return ls.id(); }) | - ranges::views::unique; + return issues; +} - // Filter regulatory elements whose refline type is stop line - auto reg_elem_sl = map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { - const auto & params = elem->getParameters(); - return params.find(lanelet::RoleNameString::RefLine) != params.end(); - }); +lanelet::validation::Issues +MissingRegulatoryElementsForStopLinesValidator::checkMissingRegulatoryElementsForStopLines( + const lanelet::LaneletMap & map) +{ + lanelet::validation::Issues issues; - // Get all line strings of stop line referred by regulatory elements - std::set sl_ids_reg_elem; - for (const auto & elem : reg_elem_sl) { - const auto & ref_lines = - elem->getParameters(lanelet::RoleName::RefLine); - for (const auto & ref_line : ref_lines) { - const auto & attrs = ref_line.attributes(); - const auto & it = attrs.find(lanelet::AttributeName::Type); - if (it != attrs.end() && it->second == lanelet::AttributeValueString::StopLine) { - sl_ids_reg_elem.insert(ref_line.id()); - } - } - } + // Get all line strings whose type is stop line + auto sl_ids = map.lineStringLayer | ranges::views::filter([](auto && ls) { + const auto & attrs = ls.attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Type); + return it != attrs.end() && it->second == lanelet::AttributeValueString::StopLine; + }) | + ranges::views::transform([](auto && ls) { return ls.id(); }) | + ranges::views::unique; + + // Filter regulatory elements whose refline type is stop line + auto reg_elem_sl = map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { + const auto & params = elem->getParameters(); + return params.find(lanelet::RoleNameString::RefLine) != params.end(); + }); - // Check if all line strings of stop line referred by regulatory elements - for (const auto & sl_id : sl_ids) { - if (sl_ids_reg_elem.find(sl_id) == sl_ids_reg_elem.end()) { - issues.emplace_back( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, sl_id, - "No regulatory element refers to this stop line."); + // Get all line strings of stop line referred by regulatory elements + std::set sl_ids_reg_elem; + for (const auto & elem : reg_elem_sl) { + const auto & ref_lines = + elem->getParameters(lanelet::RoleName::RefLine); + for (const auto & ref_line : ref_lines) { + const auto & attrs = ref_line.attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Type); + if (it != attrs.end() && it->second == lanelet::AttributeValueString::StopLine) { + sl_ids_reg_elem.insert(ref_line.id()); } } + } - return issues; + // Check if all line strings of stop line referred by regulatory elements + for (const auto & sl_id : sl_ids) { + if (sl_ids_reg_elem.find(sl_id) == sl_ids_reg_elem.end()) { + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, sl_id, + "No regulatory element refers to this stop line."); + } } -} // namespace validation -} // namespace lanelet2 \ No newline at end of file + return issues; +} + +} // namespace validation +} // namespace lanelet diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/missing_regulatory_elements_for_traffic_light.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/missing_regulatory_elements_for_traffic_light.cpp index 50a3146c..218085e6 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/missing_regulatory_elements_for_traffic_light.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/missing_regulatory_elements_for_traffic_light.cpp @@ -14,7 +14,6 @@ #include #include - #include #include #include @@ -27,68 +26,68 @@ namespace lanelet { namespace validation { -namespace +namespace { - lanelet::validation::RegisterMapValidator reg; +lanelet::validation::RegisterMapValidator reg; } - lanelet::validation::Issues MissingRegulatoryElementsForTrafficLightsValidator::operator()( - const lanelet::LaneletMap & map) - { - lanelet::validation::Issues issues; - - lanelet::autoware::validation::appendIssues( - issues, checkMissingRegulatoryElementsForTrafficLights(map)); - - return issues; - } +lanelet::validation::Issues MissingRegulatoryElementsForTrafficLightsValidator::operator()( + const lanelet::LaneletMap & map) +{ + lanelet::validation::Issues issues; - lanelet::validation::Issues - MissingRegulatoryElementsForTrafficLightsValidator::checkMissingRegulatoryElementsForTrafficLights( - const lanelet::LaneletMap & map) - { - lanelet::validation::Issues issues; + lanelet::autoware::validation::appendIssues( + issues, checkMissingRegulatoryElementsForTrafficLights(map)); - // Get all line strings whose type is traffic light - auto tl_ids = - map.lineStringLayer | ranges::views::filter([](auto && ls) { - const auto & attrs = ls.attributes(); - const auto & it = attrs.find(lanelet::AttributeName::Type); - return it != attrs.end() && it->second == lanelet::AttributeValueString::TrafficLight; - }) | - ranges::views::transform([](auto && ls) { return ls.id(); }) | ranges::views::unique; + return issues; +} - // Filter regulatory elements whose type is traffic light and has refers - auto reg_elem_tl = map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { - const auto & attrs = elem->attributes(); - const auto & it = attrs.find(lanelet::AttributeName::Subtype); - const auto & params = elem->getParameters(); - return it != attrs.end() && - it->second == lanelet::AttributeValueString::TrafficLight && - params.find(lanelet::RoleNameString::Refers) != params.end(); - }); +lanelet::validation::Issues +MissingRegulatoryElementsForTrafficLightsValidator::checkMissingRegulatoryElementsForTrafficLights( + const lanelet::LaneletMap & map) +{ + lanelet::validation::Issues issues; - // Get all line strings of traffic light referred by regulatory elements - std::set tl_ids_reg_elem; - for (const auto & elem : reg_elem_tl) { - const auto & refers = - elem->getParameters(lanelet::RoleName::Refers); - for (const auto & refer : refers) { - tl_ids_reg_elem.insert(refer.id()); - } - } + // Get all line strings whose type is traffic light + auto tl_ids = + map.lineStringLayer | ranges::views::filter([](auto && ls) { + const auto & attrs = ls.attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Type); + return it != attrs.end() && it->second == lanelet::AttributeValueString::TrafficLight; + }) | + ranges::views::transform([](auto && ls) { return ls.id(); }) | ranges::views::unique; - // Check if all line strings of traffic light referred by regulatory elements - for (const auto & tl_id : tl_ids) { - if (tl_ids_reg_elem.find(tl_id) == tl_ids_reg_elem.end()) { - issues.emplace_back( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, tl_id, - "No regulatory element refers to this traffic light."); - } + // Filter regulatory elements whose type is traffic light and has refers + auto reg_elem_tl = map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { + const auto & attrs = elem->attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + const auto & params = elem->getParameters(); + return it != attrs.end() && + it->second == lanelet::AttributeValueString::TrafficLight && + params.find(lanelet::RoleNameString::Refers) != params.end(); + }); + + // Get all line strings of traffic light referred by regulatory elements + std::set tl_ids_reg_elem; + for (const auto & elem : reg_elem_tl) { + const auto & refers = + elem->getParameters(lanelet::RoleName::Refers); + for (const auto & refer : refers) { + tl_ids_reg_elem.insert(refer.id()); } + } - return issues; + // Check if all line strings of traffic light referred by regulatory elements + for (const auto & tl_id : tl_ids) { + if (tl_ids_reg_elem.find(tl_id) == tl_ids_reg_elem.end()) { + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, tl_id, + "No regulatory element refers to this traffic light."); + } } -} // namespace validation -} // namespace lanelet2 \ No newline at end of file + return issues; +} + +} // namespace validation +} // namespace lanelet diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp index 41145d2f..43be70ec 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp @@ -13,7 +13,6 @@ // limitations under the License. #include - #include #include @@ -29,84 +28,85 @@ namespace lanelet::validation::RegisterMapValidator reg; } // namespace - lanelet::validation::Issues RegulatoryElementsDetailsForTrafficLightsValidator::operator()( - const lanelet::LaneletMap & map) - { - // All issues found by all validators - lanelet::validation::Issues issues; +lanelet::validation::Issues RegulatoryElementsDetailsForTrafficLightsValidator::operator()( + const lanelet::LaneletMap & map) +{ + // All issues found by all validators + lanelet::validation::Issues issues; - // Append issues found by each validator - lanelet::autoware::validation::appendIssues(issues, checkRegulatoryElementOfTrafficLights(map)); - return issues; - } + // Append issues found by each validator + lanelet::autoware::validation::appendIssues(issues, checkRegulatoryElementOfTrafficLights(map)); + return issues; +} - bool RegulatoryElementsDetailsForTrafficLightsValidator::isPedestrianTrafficLight( - const std::vector & traffic_lights) - { - for (const auto & tl : traffic_lights) { - const auto & attrs = tl.attributes(); - const auto & it = attrs.find(lanelet::AttributeName::Subtype); - if (it == attrs.end() || it->second != "red_green") { - return false; - } +bool RegulatoryElementsDetailsForTrafficLightsValidator::isPedestrianTrafficLight( + const std::vector & traffic_lights) +{ + for (const auto & tl : traffic_lights) { + const auto & attrs = tl.attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + if (it == attrs.end() || it->second != "red_green") { + return false; } - return true; } + return true; +} - lanelet::validation::Issues RegulatoryElementsDetailsForTrafficLightsValidator::checkRegulatoryElementOfTrafficLights( - const lanelet::LaneletMap & map) - { - lanelet::validation::Issues issues; - // filter regulatory element whose Subtype is traffic light - auto elems = - map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { - const auto & attrs = elem->attributes(); - const auto & it = attrs.find(lanelet::AttributeName::Subtype); - return it != attrs.end() && it->second == lanelet::AttributeValueString::TrafficLight; - }); +lanelet::validation::Issues +RegulatoryElementsDetailsForTrafficLightsValidator::checkRegulatoryElementOfTrafficLights( + const lanelet::LaneletMap & map) +{ + lanelet::validation::Issues issues; + // filter regulatory element whose Subtype is traffic light + auto elems = + map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { + const auto & attrs = elem->attributes(); + const auto & it = attrs.find(lanelet::AttributeName::Subtype); + return it != attrs.end() && it->second == lanelet::AttributeValueString::TrafficLight; + }); - for (const auto & elem : elems) { - // Get line strings of traffic light referred by regulatory element - auto refers = elem->getParameters(lanelet::RoleName::Refers); - // Get stop line referred by regulatory element - auto ref_lines = elem->getParameters(lanelet::RoleName::RefLine); - const auto & issue_tl = lanelet::validation::Issue( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, - lanelet::utils::getId(), - "Refers of traffic light regulatory element must have type of traffic_light."); - lanelet::autoware::validation::checkPrimitivesType( - refers, lanelet::AttributeValueString::TrafficLight, issue_tl, issues); + for (const auto & elem : elems) { + // Get line strings of traffic light referred by regulatory element + auto refers = elem->getParameters(lanelet::RoleName::Refers); + // Get stop line referred by regulatory element + auto ref_lines = elem->getParameters(lanelet::RoleName::RefLine); + const auto & issue_tl = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, + lanelet::utils::getId(), + "Refers of traffic light regulatory element must have type of traffic_light."); + lanelet::autoware::validation::checkPrimitivesType( + refers, lanelet::AttributeValueString::TrafficLight, issue_tl, issues); - const auto & issue_sl = lanelet::validation::Issue( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, - lanelet::utils::getId(), - "Refline of traffic light regulatory element must have type of stop_line."); - lanelet::autoware::validation::checkPrimitivesType( - ref_lines, lanelet::AttributeValueString::StopLine, issue_sl, issues); + const auto & issue_sl = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, + lanelet::utils::getId(), + "Refline of traffic light regulatory element must have type of stop_line."); + lanelet::autoware::validation::checkPrimitivesType( + ref_lines, lanelet::AttributeValueString::StopLine, issue_sl, issues); - if (refers.empty()) { - issues.emplace_back( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, - elem->id(), "Regulatory element of traffic light must have a traffic light(refers)."); - } - // TODO(sgk-000): Check correct behavior if regulatory element has two or more traffic light - // else if (refers.size() != 1) { - // issues.emplace_back( - // lanelet::validation::Severity::Error, - // lanelet::validation::Primitive::RegulatoryElement, elem->id(), "Regulatory element of - // traffic light must have only one traffic light(refers)."); - // } + if (refers.empty()) { + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), "Regulatory element of traffic light must have a traffic light(refers)."); + } + // TODO(sgk-000): Check correct behavior if regulatory element has two or more traffic light + // else if (refers.size() != 1) { + // issues.emplace_back( + // lanelet::validation::Severity::Error, + // lanelet::validation::Primitive::RegulatoryElement, elem->id(), "Regulatory element of + // traffic light must have only one traffic light(refers)."); + // } - // Report error if regulatory element does not have stop line and this is not a pedestrian - // traffic light - if (ref_lines.empty() && !isPedestrianTrafficLight(refers)) { - issues.emplace_back( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, - elem->id(), "Regulatory element of traffic light must have a stop line(ref_line)."); - } + // Report error if regulatory element does not have stop line and this is not a pedestrian + // traffic light + if (ref_lines.empty() && !isPedestrianTrafficLight(refers)) { + issues.emplace_back( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), "Regulatory element of traffic light must have a stop line(ref_line)."); } - return issues; } + return issues; +} } // namespace validation } // namespace lanelet diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/validator_template.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/validator_template.cpp index 0984d49c..4eacfbd0 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validators/validator_template.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/validators/validator_template.cpp @@ -18,17 +18,16 @@ namespace lanelet { namespace validation { - lanelet::validation::RegisterMapValidator reg; +lanelet::validation::RegisterMapValidator reg; - lanelet::validation::Issues ValidatorTemplate::operator()( - const lanelet::LaneletMap & map) - { - lanelet::validation::Issues issues; - - // Remove this line and write down how to append issues - (void)map; - - return issues; - } +lanelet::validation::Issues ValidatorTemplate::operator()(const lanelet::LaneletMap & map) +{ + lanelet::validation::Issues issues; + + // Remove this line and write down how to append issues + (void)map; + + return issues; } -} \ No newline at end of file +} // namespace validation +} // namespace lanelet diff --git a/map/autoware_lanelet2_map_validator/src/main.cpp b/map/autoware_lanelet2_map_validator/src/main.cpp index 905b4950..b8e8be7d 100644 --- a/map/autoware_lanelet2_map_validator/src/main.cpp +++ b/map/autoware_lanelet2_map_validator/src/main.cpp @@ -12,12 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "lanelet2_validation/Validation.h" + #include #include #include -#include "lanelet2_validation/Validation.h" #include + #include #include @@ -30,7 +32,9 @@ #define NORMAL_RED "\033[31m" #define FONT_RESET "\033[0m" -int process_requirements(YAML::Node yaml_config, const lanelet::autoware::validation::MetaConfig& validator_config) { +int process_requirements( + YAML::Node yaml_config, const lanelet::autoware::validation::MetaConfig & validator_config) +{ unsigned long warning_count = 0; unsigned long error_count = 0; lanelet::autoware::validation::MetaConfig temp_validator_config = validator_config; @@ -41,34 +45,35 @@ int process_requirements(YAML::Node yaml_config, const lanelet::autoware::valida std::vector issues; std::map temp_validation_results; - + for (YAML::Node validator : requirement["validators"]) { std::string validator_name = validator["name"].as(); temp_validator_config.command_line_config.validationConfig.checksFilter = validator_name; - - std::vector temp_issues = lanelet::autoware::validation::validateMap(temp_validator_config); - + + std::vector temp_issues = + lanelet::autoware::validation::validateMap(temp_validator_config); + if (temp_issues.empty()) { - // Validator passed - temp_validation_results[validator_name] = true; - validator["passed"] = true; + // Validator passed + temp_validation_results[validator_name] = true; + validator["passed"] = true; } else { - // Validator failed - requirement_passed = false; - warning_count += temp_issues[0].warnings().size(); - error_count += temp_issues[0].errors().size(); - temp_validation_results[validator_name] = false; - validator["passed"] = false; - YAML::Node issues_node = YAML::Node(YAML::NodeType::Sequence); - for (lanelet::validation::Issue issue : temp_issues[0].issues) { - YAML::Node issue_node; - issue_node["severity"] = lanelet::validation::toString(issue.severity); - issue_node["primitive"] = lanelet::validation::toString(issue.primitive); - issue_node["id"] = issue.id; - issue_node["message"] = issue.message; - issues_node.push_back(issue_node); - } - validator["issues"] = issues_node; + // Validator failed + requirement_passed = false; + warning_count += temp_issues[0].warnings().size(); + error_count += temp_issues[0].errors().size(); + temp_validation_results[validator_name] = false; + validator["passed"] = false; + YAML::Node issues_node = YAML::Node(YAML::NodeType::Sequence); + for (lanelet::validation::Issue issue : temp_issues[0].issues) { + YAML::Node issue_node; + issue_node["severity"] = lanelet::validation::toString(issue.severity); + issue_node["primitive"] = lanelet::validation::toString(issue.primitive); + issue_node["id"] = issue.id; + issue_node["message"] = issue.message; + issues_node.push_back(issue_node); + } + validator["issues"] = issues_node; } lanelet::autoware::validation::appendIssues(issues, std::move(temp_issues)); @@ -87,27 +92,32 @@ int process_requirements(YAML::Node yaml_config, const lanelet::autoware::valida // In order to make "passed" field above then the "validators" field in the output file. YAML::Node temp_validators = requirement["validators"]; requirement.remove("validators"); - requirement["validators"] = temp_validators; + requirement["validators"] = temp_validators; - for (const auto &result : temp_validation_results) { + for (const auto & result : temp_validation_results) { if (result.second) { - std::cout << " - " << result.first << ": " << NORMAL_GREEN << "Passed" << FONT_RESET << std::endl; + std::cout << " - " << result.first << ": " << NORMAL_GREEN << "Passed" << FONT_RESET + << std::endl; } else { - std::cout << " - " << result.first << ": " << NORMAL_RED << "Failed" << FONT_RESET << std::endl; + std::cout << " - " << result.first << ": " << NORMAL_RED << "Failed" << FONT_RESET + << std::endl; } } lanelet::validation::printAllIssues(issues); std::cout << std::endl; } - if(warning_count + error_count == 0) { - std::cout << BOLD_GREEN << "No issues were found from " << FONT_RESET << validator_config.command_line_config.mapFile << std::endl; + if (warning_count + error_count == 0) { + std::cout << BOLD_GREEN << "No issues were found from " << FONT_RESET + << validator_config.command_line_config.mapFile << std::endl; } else { if (warning_count > 0) { - std::cout << BOLD_YELLOW << "Total of " << warning_count << " warnings were found from " << FONT_RESET << validator_config.command_line_config.mapFile << std::endl; + std::cout << BOLD_YELLOW << "Total of " << warning_count << " warnings were found from " + << FONT_RESET << validator_config.command_line_config.mapFile << std::endl; } if (error_count > 0) { - std::cout << BOLD_RED << "Total of " << error_count << " errors were found from " << FONT_RESET << validator_config.command_line_config.mapFile << std::endl; + std::cout << BOLD_RED << "Total of " << error_count << " errors were found from " + << FONT_RESET << validator_config.command_line_config.mapFile << std::endl; } } @@ -123,8 +133,9 @@ int process_requirements(YAML::Node yaml_config, const lanelet::autoware::valida int main(int argc, char * argv[]) { - lanelet::autoware::validation::MetaConfig config = lanelet::autoware::validation::parseCommandLine( - argc, const_cast(argv)); // NOLINT + lanelet::autoware::validation::MetaConfig config = + lanelet::autoware::validation::parseCommandLine( + argc, const_cast(argv)); // NOLINT // Print help (Already done in parseCommandLine) if (config.command_line_config.help) { @@ -136,8 +147,8 @@ int main(int argc, char * argv[]) auto checks = lanelet::validation::availabeChecks(config.command_line_config.validationConfig.checksFilter); if (checks.empty()) { - std::cout << "No checks found matching '" << config.command_line_config.validationConfig.checksFilter - << "'\n"; + std::cout << "No checks found matching '" + << config.command_line_config.validationConfig.checksFilter << "'\n"; } else { std::cout << "The following checks are available:\n"; for (auto & check : checks) { diff --git a/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp index b03a8851..d85a3a5d 100644 --- a/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp +++ b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp @@ -12,16 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include +#include #include #include #include -#include -#include - -#include - #include +#include using lanelet::AttributeMap; using lanelet::AttributeName; @@ -147,8 +145,8 @@ TEST_F(TestSuite, ValidatorAvailability) // NOLINT for gtest "mapping.stop_line.missing_regulatory_elements," "mapping.traffic_light.missing_regulatory_elements"; - lanelet::validation::Strings validators = lanelet::validation::availabeChecks( - expected_validators_concat); + lanelet::validation::Strings validators = + lanelet::validation::availabeChecks(expected_validators_concat); uint8_t expected_num_validators = 3; std::cout << "size: " << validators.size() << std::endl; EXPECT_EQ(expected_num_validators, validators.size()); @@ -156,14 +154,12 @@ TEST_F(TestSuite, ValidatorAvailability) // NOLINT for gtest std::set expected_validators_set = { "mapping.crosswalk.missing_regulatory_elements", "mapping.stop_line.missing_regulatory_elements", - "mapping.traffic_light.missing_regulatory_elements" - }; + "mapping.traffic_light.missing_regulatory_elements"}; std::set testing_validators_set = { lanelet::validation::MissingRegulatoryElementsForCrosswalksValidator::name(), lanelet::validation::MissingRegulatoryElementsForStopLinesValidator::name(), - lanelet::validation::MissingRegulatoryElementsForTrafficLightsValidator::name() - }; + lanelet::validation::MissingRegulatoryElementsForTrafficLightsValidator::name()}; for (const auto & name : testing_validators_set) { std::cout << name << std::endl; @@ -185,7 +181,8 @@ TEST_F(TestSuite, MissingRegulatoryElementOfTrafficLight) // NOLINT for gtest const auto & issues = checker_(*test_map_ptr); uint8_t expected_num_issues = 1; - static constexpr const char * expected_message = "No regulatory element refers to this traffic light."; + static constexpr const char * expected_message = + "No regulatory element refers to this traffic light."; EXPECT_EQ(expected_num_issues, issues.size()); for (const auto & issue : issues) { EXPECT_EQ(99999, issue.id); @@ -211,7 +208,8 @@ TEST_F(TestSuite, MissingRegulatoryElementOfCrosswalk) // NOLINT for gtest const auto & issues = checker_(*test_map_ptr); uint8_t expected_num_issues = 1; - static constexpr const char * expected_message = "No regulatory element refers to this crosswalk."; + static constexpr const char * expected_message = + "No regulatory element refers to this crosswalk."; EXPECT_EQ(expected_num_issues, issues.size()); for (const auto & issue : issues) { EXPECT_EQ(99999, issue.id); @@ -234,7 +232,8 @@ TEST_F(TestSuite, MissingRegulatoryElementOfStopLine) // NOLINT for gtest const auto & issues = checker_(*test_map_ptr); uint8_t expected_num_issues = 1; - static constexpr const char * expected_message = "No regulatory element refers to this stop line."; + static constexpr const char * expected_message = + "No regulatory element refers to this stop line."; EXPECT_EQ(expected_num_issues, issues.size()); for (const auto & issue : issues) { EXPECT_EQ(99999, issue.id); diff --git a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp index 4d43d833..0f1162b9 100644 --- a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp +++ b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp @@ -12,15 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include -#include - #include #include - -#include +#include +#include #include +#include using lanelet::AttributeMap; using lanelet::AttributeName; @@ -145,21 +143,19 @@ TEST_F(TestSuite, ValidatorAvailability) // NOLINT for gtest "mapping.crosswalk.regulatory_element_details," "mapping.traffic_light.regulatory_element_details"; - lanelet::validation::Strings validators = lanelet::validation::availabeChecks( - expected_validators_concat); + lanelet::validation::Strings validators = + lanelet::validation::availabeChecks(expected_validators_concat); uint8_t expected_num_validators = 2; std::cout << "size: " << validators.size() << std::endl; EXPECT_EQ(expected_num_validators, validators.size()); std::set expected_validators_set = { "mapping.crosswalk.regulatory_element_details", - "mapping.traffic_light.regulatory_element_details" - }; + "mapping.traffic_light.regulatory_element_details"}; std::set testing_validators_set = { lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator::name(), - lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator::name() - }; + lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator::name()}; for (const auto & name : testing_validators_set) { std::cout << name << std::endl; From 37489ec8392cc98e7b94c193938efa7f930f8853 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Fri, 27 Sep 2024 17:45:23 +0900 Subject: [PATCH 12/45] Wrote detailed README.md Signed-off-by: TaikiYamada4 --- map/autoware_lanelet2_map_validator/README.md | 281 ++++++++++++++---- ...ssing_regulatory_elements_for_crosswalk.md | 19 ++ ...gulatory_element_details_for_crosswalks.md | 28 ++ ...sing_regulatory_elements_for_stop_lines.md | 19 ++ ..._regulatory_elements_for_traffic_lights.md | 19 ++ ...tory_element_details_for_traffic_lights.md | 24 ++ ...ulatory_element_details_for_crosswalks.cpp | 28 ++ 7 files changed, 362 insertions(+), 56 deletions(-) create mode 100644 map/autoware_lanelet2_map_validator/docs/crosswalk/missing_regulatory_elements_for_crosswalk.md create mode 100644 map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md create mode 100644 map/autoware_lanelet2_map_validator/docs/stop_line/missing_regulatory_elements_for_stop_lines.md create mode 100644 map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md create mode 100644 map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md diff --git a/map/autoware_lanelet2_map_validator/README.md b/map/autoware_lanelet2_map_validator/README.md index 29d3d25e..2b9fa55c 100644 --- a/map/autoware_lanelet2_map_validator/README.md +++ b/map/autoware_lanelet2_map_validator/README.md @@ -1,60 +1,229 @@ # autoware_lanelet2_map_validator `autoware_lanelet2_map_validator` is a tool to validate Lanelet2 maps to ensure that Autoware can work properly with it. +This validation tool is an extension of [lanelet2_validation](https://github.com/fzi-forschungszentrum-informatik/Lanelet2/tree/master/lanelet2_validation) so that Autoware specific rules can be applied. -The requirements for lanelet2 maps are described in [Vector Map creation requirement specifications (in Autoware Documentation)](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/map/map-requirements/vector-map-requirements-overview/). - -| ID | Requirements | -| -------- | ------------------------------------------------------- | -| vm-01-01 | Lanelet basics | -| vm-01-02 | Allowance for lane changes | -| vm-01-03 | Linestring sharing | -| vm-01-04 | Sharing of the centerline of lanes for opposing traffic | -| vm-01-05 | Lane geometry | -| vm-01-06 | Line position (1) | -| vm-01-07 | Line position (2) | -| vm-01-08 | Line position (3) | -| vm-01-09 | Speed limits | -| vm-01-10 | Centerline | -| vm-01-11 | Centerline connection (1) | -| vm-01-12 | Centerline connection (2) | -| vm-01-13 | Roads with no centerline (1) | -| vm-01-14 | Roads with no centerline (2) | -| vm-01-15 | Road shoulder | -| vm-01-16 | Road shoulder Linestring sharing | -| vm-01-17 | Side strip | -| vm-01-18 | Side strip Linestring sharing | -| vm-01-19 | Walkway | -| vm-02-01 | Stop line alignment | -| vm-02-02 | Stop sign | -| vm-03-01 | Intersection criteria | -| vm-03-02 | Lanelet's turn direction and virtual | -| vm-03-03 | Lanelet width in the intersection | -| vm-03-04 | Lanelet creation in the intersection | -| vm-03-05 | Lanelet division in the intersection | -| vm-03-06 | Guide lines in the intersection | -| vm-03-07 | Multiple lanelets in the intersection | -| vm-03-08 | Intersection Area range | -| vm-03-09 | Range of Lanelet in the intersection | -| vm-03-10 | Right of way (with signal) | -| vm-03-11 | Right of way (without signal) | -| vm-03-12 | Right of way supplements | -| vm-03-13 | Merging from private area, sidewalk | -| vm-03-14 | Road marking | -| vm-03-15 | Exclusive bicycle lane | -| vm-04-01 | Traffic light basics | -| vm-04-02 | Traffic light position and size | -| vm-04-03 | Traffic light lamps | -| vm-05-01 | Crosswalks across the road | -| vm-05-02 | Crosswalks with pedestrian signals | -| vm-05-03 | Deceleration for safety at crosswalks | -| vm-05-04 | Fences | -| vm-06-01 | Buffer Zone | -| vm-06-02 | No parking signs | -| vm-06-03 | No stopping signs | -| vm-06-04 | No stopping sections | -| vm-06-05 | Detection area | -| vm-07-01 | Vector Map creation range | -| vm-07-02 | Range of detecting pedestrians who enter the road | -| vm-07-03 | Guardrails, guard pipes, fences | -| vm-07-04 | Ellipsoidal height | +**Note that this validator is still on construction that there are only a few rules and a template to define those rules.** + +The official Autoware requirements for lanelet2 maps are described in [Vector Map creation requirement specifications (in Autoware Documentation)](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/map/map-requirements/vector-map-requirements-overview/). + +## How to use + +Basically, you can use the following command to execute `autoware_lanelet2_map_validator`. However, note that `autoware_lanelet2_map_validator` is a ROS/rclcpp free tool, so you can just run the built executable whatever way. + +```bash +ros2 run autoware_lanelet2_map_validator autoware_lanelet2_map_validator +``` + +### Run ALL validators + +You can use `autoware_lanelet2_map_validator` with the following command. This will run all validators including the default built-in validators in the [lanelet2_validation](https://github.com/fzi-forschungszentrum-informatik/Lanelet2/tree/master/lanelet2_validation). + +```bash +ros2 run autoware_lanelet2_map_validator autoware_lanelet2_map_validator --map_file path/to_your/lanelet2_map.osm +``` + +### Run a specific validator + +`autoware_lanelet2_map_validator` consists of multiple small validators in order to realize complex requirements with a combination of them. +If you want to call a few validators, you can select them with the `--validator, -v` option. + +```bash +ros2 run autoware_lanelet2_map_validator autoware_lanelet2_map_validator --map_file path/to_your/lanelet2_map.osm --validator mapping.traffic_light.missing_regulatory_elements +``` + +You can get a list of available validators with the `--print, -p` option. + +```bash +ros2 run autoware_lanelet2_map_validator autoware_lanelet2_map_validator --print +``` + +### Run with a requirement set + +You can run `autoware_lanelet2_map_validator` with a yaml file input that follows the structure like this + +```yaml +requirements: + - id: vm-01-01 + validators: + - name: mapping.crosswalk.missing_regulatory_elements + - name: mapping.crosswalk.regulatory_element_details + - id: vm-01-02 + validators: + - name: mapping.traffic_light.missing_regulatory_elements + - name: mapping.traffic_light.regulatory_element_details + - id: vm-01-03 + validators: + - name: mapping.stop_line.missing_regulatory_elements +``` + +- MUST have a single `requirements` field. +- The `requirements` field MUST be a list of requirements. A requirement MUST have + - `id` : The id of the requirement. + - `validators` : A list of validators that structures the requirement. + - A validator MUST be given with its name on the `name` field. + - The name list of available validators can be obtained from the `--print` option. +- The user can write any other field (like `version`) besides `requirements`. + +Then, the `autoware_lanelet2_map_validator` will scan through the input yaml file given by the `--requirements_file, -r` option, and output the validation results to the directory given by the `--output_file_path, -o` option. + +```bash +ros2 run autoware_lanelet2_map_validator autoware_lanelet2_map_validator --requirements_file ./requirements_set.yaml --output_file_path ./ +``` + +When the `requirements_file` is thown to `autoware_lanelet2_map_validator`, it will output a `lanelet2_validation_results.yaml` file which looks like the following. + +```yaml +requirements: + - id: vm-01-01 + passed: false + validators: + - name: mapping.crosswalk.missing_regulatory_elements + passed: false + issues: + - severity: Error + primitive: lanelet + id: 163 + message: No regulatory element refers to this crosswalk. + - severity: Error + primitive: lanelet + id: 164 + message: No regulatory element refers to this crosswalk. + - severity: Error + primitive: lanelet + id: 165 + message: No regulatory element refers to this crosswalk. + - severity: Error + primitive: lanelet + id: 166 + message: No regulatory element refers to this crosswalk. + - name: mapping.crosswalk.regulatory_element_details + passed: true + - id: vm-01-02 + passed: false + validators: + - name: mapping.traffic_light.missing_regulatory_elements + passed: true + - name: mapping.traffic_light.regulatory_element_details + passed: false + issues: + - severity: Error + primitive: regulatory element + id: 9896 + message: Regulatory element of traffic light must have a stop line(ref_line). + - severity: Error + primitive: regulatory element + id: 9918 + message: Regulatory element of traffic light must have a stop line(ref_line). + - severity: Error + primitive: regulatory element + id: 9838 + message: Regulatory element of traffic light must have a stop line(ref_line). + - severity: Error + primitive: regulatory element + id: 9874 + message: Regulatory element of traffic light must have a stop line(ref_line). + - id: vm-01-03 + passed: true + validators: + - name: mapping.stop_line.missing_regulatory_elements + passed: true +``` + +- `lanelet2_validation_results.yaml` inherits the input `requirements_file` and add results to it. +- `autoware_lanelet2_map_validator` adds a boolean `passed` field to each requirement. If all validators of the requirement have been passed, the `passed` field of the requirement will be `true` (`false` if not). +- The `passed` field is also given to each validator. If the validator found any issues the `passed` field will turn to be `false` (`true` if not), and adds an `issues` field which is a list of issues found. Each issues contains information of `serverity`, `primitive`, `id`, and `message`. + +### Available command options + +| option | description | +| ------ | ----------- | +| `-h, --help` | Explains about this tool and show a list of options | +| `--print` | Only print all avalible checker, but dont run them | +| `-m, --map_file` | Path to the map to be validated | +| `-r, --requirements_file` | Path to the yaml file where the list of requirements and validations is written | +| `-o, --output_file_path` | Path of the yaml file where the list of validation results will be written | +| `-v, --validator` | 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 | +| `-p, --projector` | Projector used for loading lanelet map. Available projectors are: mgrs, utm, transverse_mercator. (default: mgrs) | +| `-l, --location` | Location of the map (for instanciating the traffic rules), e.g. de for Germany | +| `--participants` | Participants for which the routing graph will be instanciated (default: vehicle) | +| `--lat` | latitude coordinate of map origin. This is required for the transverse mercator and utm projector. | +| `--lon` | longitude coofdinate of map origin. This is required for the transverse mercator and utm projector. | + +### Available validators + +Since there will be hundreds of validators in the future, the documents for each validators should categorized in the docs file. +The directory structure should be the same to that of the `src/lib/validators` directory. + +#### Stop Line + +- [mapping.stop_line.missing_regulatory_elements](./docs/stop_line/missing_regulatory_elements_for_stop_lines.md) + +#### Traffic Light + +- [mapping.traffic_light.missing_regulatory_elements](./docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md) +- [mapping.traffic_light.regulatory_element_details](./docs/traffic_light/regulatory_element_details_for_traffic_lights.md) + +#### Crosswalk + +- [mapping.crosswalk.missing_regulatory_elements](./docs/crosswalk/missing_regulatory_elements_for_crosswalk.md) +- [mapping.crosswalk.regulatory_element_details](./docs/crosswalk/regulatory_element_details_for_crosswalks.md) + +## Relationship between requirements and validators + +The Validators column will be blank if it hasn't be implemented. + +| ID | Requirements | Validators | +| -------- | ------------------------------------------------------- | ---------- | +| vm-01-01 | Lanelet basics | | +| vm-01-02 | Allowance for lane changes | | +| vm-01-03 | Linestring sharing | | +| vm-01-04 | Sharing of the centerline of lanes for opposing traffic | | +| vm-01-05 | Lane geometry | | +| vm-01-06 | Line position (1) | | +| vm-01-07 | Line position (2) | | +| vm-01-08 | Line position (3) | | +| vm-01-09 | Speed limits | | +| vm-01-10 | Centerline | | +| vm-01-11 | Centerline connection (1) | | +| vm-01-12 | Centerline connection (2) | | +| vm-01-13 | Roads with no centerline (1) | | +| vm-01-14 | Roads with no centerline (2) | | +| vm-01-15 | Road shoulder | | +| vm-01-16 | Road shoulder Linestring sharing | | +| vm-01-17 | Side strip | | +| vm-01-18 | Side strip Linestring sharing | | +| vm-01-19 | Walkway | | +| vm-02-01 | Stop line alignment | | +| vm-02-02 | Stop sign | | +| vm-03-01 | Intersection criteria | | +| vm-03-02 | Lanelet's turn direction and virtual | | +| vm-03-03 | Lanelet width in the intersection | | +| vm-03-04 | Lanelet creation in the intersection | | +| vm-03-05 | Lanelet division in the intersection | | +| vm-03-06 | Guide lines in the intersection | | +| vm-03-07 | Multiple lanelets in the intersection | | +| vm-03-08 | Intersection Area range | | +| vm-03-09 | Range of Lanelet in the intersection | | +| vm-03-10 | Right of way (with signal) | | +| vm-03-11 | Right of way (without signal) | | +| vm-03-12 | Right of way supplements | | +| vm-03-13 | Merging from private area, sidewalk | | +| vm-03-14 | Road marking | | +| vm-03-15 | Exclusive bicycle lane | | +| vm-04-01 | Traffic light basics | [mapping.traffic_light.missing_regulatory_elements](./docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md), [mapping.traffic_light.regulatory_element_details](./docs/traffic_light/regulatory_element_details_for_traffic_lights.md) (Undone) | +| vm-04-02 | Traffic light position and size | | +| vm-04-03 | Traffic light lamps | | +| vm-05-01 | Crosswalks across the road | [mapping.crosswalk.missing_regulatory_elements](./docs/crosswalk/missing_regulatory_elements_for_crosswalk.md), [mapping.crosswalk.regulatory_element_details](./docs/crosswalk/regulatory_element_details_for_crosswalks.md) | +| vm-05-02 | Crosswalks with pedestrian signals | | +| vm-05-03 | Deceleration for safety at crosswalks | | +| vm-05-04 | Fences | | +| vm-06-01 | Buffer Zone | | +| vm-06-02 | No parking signs | | +| vm-06-03 | No stopping signs | | +| vm-06-04 | No stopping sections | | +| vm-06-05 | Detection area | | +| vm-07-01 | Vector Map creation range | | +| vm-07-02 | Range of detecting pedestrians who enter the road | | +| vm-07-03 | Guardrails, guard pipes, fences | | +| vm-07-04 | Ellipsoidal height | | diff --git a/map/autoware_lanelet2_map_validator/docs/crosswalk/missing_regulatory_elements_for_crosswalk.md b/map/autoware_lanelet2_map_validator/docs/crosswalk/missing_regulatory_elements_for_crosswalk.md new file mode 100644 index 00000000..e07210d3 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/docs/crosswalk/missing_regulatory_elements_for_crosswalk.md @@ -0,0 +1,19 @@ +# missing_regulator_elements_for_crosswalk + +## Validator name + +mapping.crosswalk.missing_regulatory_elements + +## Feature + +This validator checks whether each `crosswalk` subtype lanelet has a relavant regulatory element. +The issue specifies the crosswalk "lanelet" as the **primitive**, and the lanelet ID will be specified as the **ID**. + +| Message | Severity | Description | +| ------- | -------- | ----------- | +| "No regulatory element refers to this crosswalk." | Error | There is a `crosswalk` subtype lanelet that hasn't been referred to any regulatory element. | + +## Related source codes + +- missing_regulatory_elements_for_crosswalk.hpp +- missing_regulatory_elements_for_crosswalk.cpp diff --git a/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md b/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md new file mode 100644 index 00000000..6c94498b --- /dev/null +++ b/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md @@ -0,0 +1,28 @@ +# regulatory_element_details_for_crosswalks + +## Validator name + +mapping.crosswalk.regulatory_element_details + +## Feature + +This validator checks whether the details in the `crosswalk` subtype regulatory elements are valid. +This validator checks seven types of issues. + +All output issues specify the crosswalk "lanelet" as the **primitive**, and the lanelet ID will be specified as the **ID**. + +| Message | Severity | Description | +| ------- | -------- | ----------- | +| "Refers of crosswalk regulatory element must have type of crosswalk." | Error | There is a `crosswalk` subtype regulatory element whose `refers` is not a `crosswalk` subtype lanelet. | +| "Refline of crosswalk regulatory element must have type of stopline." | Error | There is a `crosswalk` subtype regulatory element whose `ref_line` is not a `stop_line` type linestring. | +| "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon." | Error | There is a `crosswalk` subtype regulatory element whose `crosswalk_polygon` is not a `crosswalk_polygon` type polygon. | +| "Regulatory element of cross walk must have lanelet of crosswalk(refers)." | Error | There is a `crosswalk` subtype regulatory element that has no `refers`es. | +| "Regulatory element of cross walk must have only one lanelet of crosswalk(refers)." | Error | There is a `crosswalk` subtype regulatory element that has multiple `refers`es. | +| "Regulatory element of cross walk does not have stop line(ref_line)." | Info | There is a `crosswalk` subtype regulatory element that has no `ref_line`s | +| "Regulatory element of cross walk is nice to have crosswalk_polygon." | Warning | There is a `crosswalk` subtype regulatory element that has no `crosswalk_polygon`s. | +| "Regulatory element of cross walk must have only one crosswalk_polygon." | Error | There is a `crosswalk` subtype regulatory element that has multiple `crosswalk_polygon`s. | + +## Related source codes + +- regulatory_element_details_for_crosswalks.hpp +- regulatory_element_details_for_crosswalks.cpp diff --git a/map/autoware_lanelet2_map_validator/docs/stop_line/missing_regulatory_elements_for_stop_lines.md b/map/autoware_lanelet2_map_validator/docs/stop_line/missing_regulatory_elements_for_stop_lines.md new file mode 100644 index 00000000..26a72eec --- /dev/null +++ b/map/autoware_lanelet2_map_validator/docs/stop_line/missing_regulatory_elements_for_stop_lines.md @@ -0,0 +1,19 @@ +# missing_regulator_elements_for_stop_lines + +## Validator name + +mapping.stop_line.missing_regulatory_elements + +## Feature + +This validator checks whether each `stop_line` type linestring has a relavant regulatory element. +The issue specifies the stop_line "linestring" as the **primitive**, and the lanelet ID will be specified as the **ID**. + +| Message | Severity | Description | +| ------- | -------- | ----------- | +| "No regulatory element refers to this stop line." | Error | There is a `stop_line` type linestring that hasn't been referred to any regulatory element. | + +## Related source codes + +- missing_regulatory_elements_for_stop_line.cpp +- missing_regulatory_elements_for_stop_line.hpp diff --git a/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md b/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md new file mode 100644 index 00000000..8acf2097 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md @@ -0,0 +1,19 @@ +# missing_regulator_elements_for_traffic_lights + +## Validator name + +mapping.traffic_light.missing_regulatory_elements + +## Feature + +This validator checks whether each `traffic_light` type linestring has a relavant regulatory element. +The output issue specifies the traffic_light "linestring" as the **primitive**, and the linestring ID will be specified as the **ID**. + +| Message | Severity | Description | +| ------- | -------- | ----------- | +| "No regulatory element refers to this traffic light." | Error | There is a `traffic_light` type linestring that hasn't been referred to any regulatory element. | + +## Related source codes + +- missing_regulatory_elements_for_traffic_light.hpp +- missing_regulatory_elements_for_traffic_light.cpp diff --git a/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md b/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md new file mode 100644 index 00000000..254d8010 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md @@ -0,0 +1,24 @@ +# regulatory_element_details_for_traffic_lights + +## Validator name + +mapping.traffic_light.regulatory_element_details + +## Feature + +This validator checks whether the details in the `traffic_light` subtype regulatory elements are valid. +This validator checks four types of issues. + +All output issues specify the traffic_light "linestring" as the **primitive**, and the linestring ID will be specified as the **ID**. + +| Message | Severity | Description | +| ------- | -------- | ----------- | +| "Refers of traffic light regulatory element must have type of traffic_light." | Error | There is a `traffic_light` subtype regulatory element whose `refers` is not a `traffic_light` type linestring. | +| "Refline of traffic light regulatory element must have type of stop_line." | Error | There is a `traffic_light` subtype regulatory element whose `ref_line` is not a `stop_line` type linestring. | +| "Regulatory element of traffic light must have a traffic light(refers)." | Error | There is a `traffic_light` subtype regulatory element that has no `refers`es. | +| "Regulatory element of traffic light must have a stop line(ref_line)." | Error | There is a `traffic_light` subtype regulatory element that has no `ref_line`s | + +## Related source codes + +- regulatory_element_details_for_traffic_lights.hpp +- regulatory_element_details_for_traffic_lights.cpp diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp index b04a0eb0..b1934693 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp @@ -61,6 +61,7 @@ RegulatoryElementsDetailsForCrosswalksValidator::checkRegulatoryElementOfCrosswa auto crosswalk_polygons = elem->getParameters( lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon); +<<<<<<< HEAD const auto & issue_cw = lanelet::validation::Issue( lanelet::validation::Severity::Error, lanelet::validation::Primitive::Lanelet, lanelet::utils::getId(), @@ -83,6 +84,33 @@ RegulatoryElementsDetailsForCrosswalksValidator::checkRegulatoryElementOfCrosswa lanelet::autoware::validation::checkPrimitivesType( crosswalk_polygons, lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon, issue_poly, issues); +======= + // If this is a crosswalk type regulatory element, the "refers" has to be a "crosswalk" subtype lanelet + const auto & issue_cw = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::Lanelet, + lanelet::utils::getId(), + "Refers of crosswalk regulatory element must have type of crosswalk."); + lanelet::autoware::validation::checkPrimitivesType( + refers, lanelet::AttributeValueString::Lanelet, lanelet::AttributeValueString::Crosswalk, + issue_cw, issues); + + // If this is a crosswalk type regulatory element, the "ref_line" has to be a "stop_line" type linestring + const auto & issue_sl = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, + lanelet::utils::getId(), + "Refline of crosswalk regulatory element must have type of stopline."); + lanelet::autoware::validation::checkPrimitivesType( + ref_lines, lanelet::AttributeValueString::StopLine, issue_sl, issues); + + // If this is a crosswalk type regulatory element, the "crosswalk_polygon" has to be a "crosswalk_polygon" type polygon + const auto & issue_poly = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::Polygon, + lanelet::utils::getId(), + "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon."); + lanelet::autoware::validation::checkPrimitivesType( + crosswalk_polygons, lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon, + issue_poly, issues); +>>>>>>> 68f1042 (Wrote detailed README.md) // Report warning if regulatory element does not have crosswalk polygon if (crosswalk_polygons.empty()) { From b653c8490bf1b2968d6d4a3519a914bc41e7739d Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Fri, 27 Sep 2024 17:53:46 +0900 Subject: [PATCH 13/45] Fixed commit mistake Signed-off-by: TaikiYamada4 --- ...ulatory_element_details_for_crosswalks.cpp | 25 ------------------- 1 file changed, 25 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp index b1934693..9a629146 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp @@ -61,30 +61,6 @@ RegulatoryElementsDetailsForCrosswalksValidator::checkRegulatoryElementOfCrosswa auto crosswalk_polygons = elem->getParameters( lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon); -<<<<<<< HEAD - const auto & issue_cw = lanelet::validation::Issue( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::Lanelet, - lanelet::utils::getId(), - "Refers of crosswalk regulatory element must have type of crosswalk."); - lanelet::autoware::validation::checkPrimitivesType( - refers, lanelet::AttributeValueString::Lanelet, lanelet::AttributeValueString::Crosswalk, - issue_cw, issues); - - const auto & issue_sl = lanelet::validation::Issue( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, - lanelet::utils::getId(), - "Refline of crosswalk regulatory element must have type of stopline."); - lanelet::autoware::validation::checkPrimitivesType( - ref_lines, lanelet::AttributeValueString::StopLine, issue_sl, issues); - - const auto & issue_poly = lanelet::validation::Issue( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::Polygon, - lanelet::utils::getId(), - "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon."); - lanelet::autoware::validation::checkPrimitivesType( - crosswalk_polygons, lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon, - issue_poly, issues); -======= // If this is a crosswalk type regulatory element, the "refers" has to be a "crosswalk" subtype lanelet const auto & issue_cw = lanelet::validation::Issue( lanelet::validation::Severity::Error, lanelet::validation::Primitive::Lanelet, @@ -110,7 +86,6 @@ RegulatoryElementsDetailsForCrosswalksValidator::checkRegulatoryElementOfCrosswa lanelet::autoware::validation::checkPrimitivesType( crosswalk_polygons, lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon, issue_poly, issues); ->>>>>>> 68f1042 (Wrote detailed README.md) // Report warning if regulatory element does not have crosswalk polygon if (crosswalk_polygons.empty()) { From 27b354d438418a3eacf4e3b5b6dbf1c3f23affbe Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Fri, 27 Sep 2024 18:34:40 +0900 Subject: [PATCH 14/45] Renew input command option to `-i` from `-r`. Fixed mistakes in README.md Signed-off-by: TaikiYamada4 --- map/autoware_lanelet2_map_validator/README.md | 14 +++++++------- .../autoware_requirement_set.yaml | 9 +++++++++ .../regulatory_element_details_for_crosswalks.md | 2 +- ...ulatory_element_details_for_traffic_lights.md | 2 +- .../src/lib/cli.cpp | 16 ++++++++-------- .../test/test_requirement_set.yaml | 13 +++++++++++++ 6 files changed, 39 insertions(+), 17 deletions(-) create mode 100644 map/autoware_lanelet2_map_validator/autoware_requirement_set.yaml create mode 100644 map/autoware_lanelet2_map_validator/test/test_requirement_set.yaml diff --git a/map/autoware_lanelet2_map_validator/README.md b/map/autoware_lanelet2_map_validator/README.md index 2b9fa55c..90336b27 100644 --- a/map/autoware_lanelet2_map_validator/README.md +++ b/map/autoware_lanelet2_map_validator/README.md @@ -65,13 +65,13 @@ requirements: - The name list of available validators can be obtained from the `--print` option. - The user can write any other field (like `version`) besides `requirements`. -Then, the `autoware_lanelet2_map_validator` will scan through the input yaml file given by the `--requirements_file, -r` option, and output the validation results to the directory given by the `--output_file_path, -o` option. +Then, the `autoware_lanelet2_map_validator` will scan through the input yaml file given by the `--input_requirements, -i` option, and output the validation results to the directory given by the `--output_directory, -o` option. ```bash -ros2 run autoware_lanelet2_map_validator autoware_lanelet2_map_validator --requirements_file ./requirements_set.yaml --output_file_path ./ +ros2 run autoware_lanelet2_map_validator autoware_lanelet2_map_validator --input_requirements autoware_requirements_set.yaml --output_directory ./ ``` -When the `requirements_file` is thown to `autoware_lanelet2_map_validator`, it will output a `lanelet2_validation_results.yaml` file which looks like the following. +When the `input_requirements` is thown to `autoware_lanelet2_map_validator`, it will output a `lanelet2_validation_results.yaml` file which looks like the following. ```yaml requirements: @@ -130,9 +130,9 @@ requirements: passed: true ``` -- `lanelet2_validation_results.yaml` inherits the input `requirements_file` and add results to it. +- `lanelet2_validation_results.yaml` inherits the yaml file of `input_requirements` and add results to it. - `autoware_lanelet2_map_validator` adds a boolean `passed` field to each requirement. If all validators of the requirement have been passed, the `passed` field of the requirement will be `true` (`false` if not). -- The `passed` field is also given to each validator. If the validator found any issues the `passed` field will turn to be `false` (`true` if not), and adds an `issues` field which is a list of issues found. Each issues contains information of `serverity`, `primitive`, `id`, and `message`. +- The `passed` field is also given to each validator. If the validator found any issues the `passed` field will turn to be `false` (`true` if not), and adds an `issues` field which is a list of issues found. Each issues contains information of `severity`, `primitive`, `id`, and `message`. ### Available command options @@ -141,8 +141,8 @@ requirements: | `-h, --help` | Explains about this tool and show a list of options | | `--print` | Only print all avalible checker, but dont run them | | `-m, --map_file` | Path to the map to be validated | -| `-r, --requirements_file` | Path to the yaml file where the list of requirements and validations is written | -| `-o, --output_file_path` | Path of the yaml file where the list of validation results will be written | +| `-i, --input_requirements` | Path to the yaml file where the list of requirements and validations is written | +| `-o, --output_directory` | Directory to save the list of validation results in a yaml format | | `-v, --validator` | 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 | | `-p, --projector` | Projector used for loading lanelet map. Available projectors are: mgrs, utm, transverse_mercator. (default: mgrs) | | `-l, --location` | Location of the map (for instanciating the traffic rules), e.g. de for Germany | diff --git a/map/autoware_lanelet2_map_validator/autoware_requirement_set.yaml b/map/autoware_lanelet2_map_validator/autoware_requirement_set.yaml new file mode 100644 index 00000000..9437fb00 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/autoware_requirement_set.yaml @@ -0,0 +1,9 @@ +requirements: + - id: vm-04-01 + validators: + - name: mapping.crosswalk.missing_regulatory_elements + - name: mapping.crosswalk.regulatory_element_details + - id: vm-05-01 + validators: + - name: mapping.traffic_light.missing_regulatory_elements + - name: mapping.traffic_light.regulatory_element_details diff --git a/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md b/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md index 6c94498b..8d423b00 100644 --- a/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md +++ b/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md @@ -9,7 +9,7 @@ mapping.crosswalk.regulatory_element_details This validator checks whether the details in the `crosswalk` subtype regulatory elements are valid. This validator checks seven types of issues. -All output issues specify the crosswalk "lanelet" as the **primitive**, and the lanelet ID will be specified as the **ID**. +All output issues specify the crosswalk "regulatory element" as the **primitive**, and the lanelet ID will be specified as the **ID**. | Message | Severity | Description | | ------- | -------- | ----------- | diff --git a/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md b/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md index 254d8010..dfa58c28 100644 --- a/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md +++ b/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md @@ -9,7 +9,7 @@ mapping.traffic_light.regulatory_element_details This validator checks whether the details in the `traffic_light` subtype regulatory elements are valid. This validator checks four types of issues. -All output issues specify the traffic_light "linestring" as the **primitive**, and the linestring ID will be specified as the **ID**. +All output issues specify the traffic_light "regulatory element" as the **primitive**, and the linestring ID will be specified as the **ID**. | Message | Severity | Description | | ------- | -------- | ----------- | diff --git a/map/autoware_lanelet2_map_validator/src/lib/cli.cpp b/map/autoware_lanelet2_map_validator/src/lib/cli.cpp index 0aef833b..66622b29 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/cli.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/cli.cpp @@ -34,11 +34,11 @@ MetaConfig parseCommandLine(int argc, const char * argv[]) ("map_file,m", po::value(), "Path to the map to be validated") - ("requirements_file,r", po::value(), - "Path to the yaml file where the list of requirements and validations is written") + ("input_requirements,i", po::value(), + "Path to the yaml file where the list of requirements and validators is written") - ("output_file_path,o", po::value(), - "Path of the yaml file where the list of validation results will be written") + ("output_directory,o", po::value(), + "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 " @@ -83,11 +83,11 @@ MetaConfig parseCommandLine(int argc, const char * argv[]) config.command_line_config.mapFile = vm["map_file"].as(); } - if (vm.count("requirements_file") != 0) { - config.requirements_file = vm["requirements_file"].as(); + if (vm.count("input_requirements") != 0) { + config.requirements_file = vm["input_requirements"].as(); } - if (vm.count("output_file_path") != 0) { - config.output_file_path = vm["output_file_path"].as(); + if (vm.count("output_directory") != 0) { + config.output_file_path = vm["output_directory"].as(); } if ( (vm.count("lat") != 0 && vm.count("lon") != 0) && diff --git a/map/autoware_lanelet2_map_validator/test/test_requirement_set.yaml b/map/autoware_lanelet2_map_validator/test/test_requirement_set.yaml new file mode 100644 index 00000000..19e5487f --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/test_requirement_set.yaml @@ -0,0 +1,13 @@ +version: 0.0.1 +requirements: + - id: test-01 + validators: + - name: mapping.crosswalk.missing_regulatory_elements + - name: mapping.crosswalk.regulatory_element_details + - id: test-02 + validators: + - name: mapping.traffic_light.missing_regulatory_elements + - name: mapping.traffic_light.regulatory_element_details + - id: test-03 + validators: + - name: mapping.stop_line.missing_regulatory_elements From 9014a3c255e5d3130fc53c000ef8d8cd1f799644 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 27 Sep 2024 09:38:07 +0000 Subject: [PATCH 15/45] style(pre-commit): autofix --- map/autoware_lanelet2_map_validator/README.md | 132 +++++++++--------- ...ssing_regulatory_elements_for_crosswalk.md | 6 +- ...gulatory_element_details_for_crosswalks.md | 20 +-- ...sing_regulatory_elements_for_stop_lines.md | 6 +- ..._regulatory_elements_for_traffic_lights.md | 6 +- ...tory_element_details_for_traffic_lights.md | 12 +- .../package.xml | 1 - ...ulatory_element_details_for_crosswalks.cpp | 49 ++++--- 8 files changed, 117 insertions(+), 115 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/README.md b/map/autoware_lanelet2_map_validator/README.md index 90336b27..bb346a49 100644 --- a/map/autoware_lanelet2_map_validator/README.md +++ b/map/autoware_lanelet2_map_validator/README.md @@ -136,19 +136,19 @@ requirements: ### Available command options -| option | description | -| ------ | ----------- | -| `-h, --help` | Explains about this tool and show a list of options | -| `--print` | Only print all avalible checker, but dont run them | -| `-m, --map_file` | Path to the map to be validated | -| `-i, --input_requirements` | Path to the yaml file where the list of requirements and validations is written | -| `-o, --output_directory` | Directory to save the list of validation results in a yaml format | -| `-v, --validator` | 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 | -| `-p, --projector` | Projector used for loading lanelet map. Available projectors are: mgrs, utm, transverse_mercator. (default: mgrs) | -| `-l, --location` | Location of the map (for instanciating the traffic rules), e.g. de for Germany | -| `--participants` | Participants for which the routing graph will be instanciated (default: vehicle) | -| `--lat` | latitude coordinate of map origin. This is required for the transverse mercator and utm projector. | -| `--lon` | longitude coofdinate of map origin. This is required for the transverse mercator and utm projector. | +| option | description | +| -------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `-h, --help` | Explains about this tool and show a list of options | +| `--print` | Only print all avalible checker, but dont run them | +| `-m, --map_file` | Path to the map to be validated | +| `-i, --input_requirements` | Path to the yaml file where the list of requirements and validations is written | +| `-o, --output_directory` | Directory to save the list of validation results in a yaml format | +| `-v, --validator` | 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 | +| `-p, --projector` | Projector used for loading lanelet map. Available projectors are: mgrs, utm, transverse_mercator. (default: mgrs) | +| `-l, --location` | Location of the map (for instanciating the traffic rules), e.g. de for Germany | +| `--participants` | Participants for which the routing graph will be instanciated (default: vehicle) | +| `--lat` | latitude coordinate of map origin. This is required for the transverse mercator and utm projector. | +| `--lon` | longitude coofdinate of map origin. This is required for the transverse mercator and utm projector. | ### Available validators @@ -173,57 +173,57 @@ The directory structure should be the same to that of the `src/lib/validators` d The Validators column will be blank if it hasn't be implemented. -| ID | Requirements | Validators | -| -------- | ------------------------------------------------------- | ---------- | -| vm-01-01 | Lanelet basics | | -| vm-01-02 | Allowance for lane changes | | -| vm-01-03 | Linestring sharing | | -| vm-01-04 | Sharing of the centerline of lanes for opposing traffic | | -| vm-01-05 | Lane geometry | | -| vm-01-06 | Line position (1) | | -| vm-01-07 | Line position (2) | | -| vm-01-08 | Line position (3) | | -| vm-01-09 | Speed limits | | -| vm-01-10 | Centerline | | -| vm-01-11 | Centerline connection (1) | | -| vm-01-12 | Centerline connection (2) | | -| vm-01-13 | Roads with no centerline (1) | | -| vm-01-14 | Roads with no centerline (2) | | -| vm-01-15 | Road shoulder | | -| vm-01-16 | Road shoulder Linestring sharing | | -| vm-01-17 | Side strip | | -| vm-01-18 | Side strip Linestring sharing | | -| vm-01-19 | Walkway | | -| vm-02-01 | Stop line alignment | | -| vm-02-02 | Stop sign | | -| vm-03-01 | Intersection criteria | | -| vm-03-02 | Lanelet's turn direction and virtual | | -| vm-03-03 | Lanelet width in the intersection | | -| vm-03-04 | Lanelet creation in the intersection | | -| vm-03-05 | Lanelet division in the intersection | | -| vm-03-06 | Guide lines in the intersection | | -| vm-03-07 | Multiple lanelets in the intersection | | -| vm-03-08 | Intersection Area range | | -| vm-03-09 | Range of Lanelet in the intersection | | -| vm-03-10 | Right of way (with signal) | | -| vm-03-11 | Right of way (without signal) | | -| vm-03-12 | Right of way supplements | | -| vm-03-13 | Merging from private area, sidewalk | | -| vm-03-14 | Road marking | | -| vm-03-15 | Exclusive bicycle lane | | +| ID | Requirements | Validators | +| -------- | ------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| vm-01-01 | Lanelet basics | | +| vm-01-02 | Allowance for lane changes | | +| vm-01-03 | Linestring sharing | | +| vm-01-04 | Sharing of the centerline of lanes for opposing traffic | | +| vm-01-05 | Lane geometry | | +| vm-01-06 | Line position (1) | | +| vm-01-07 | Line position (2) | | +| vm-01-08 | Line position (3) | | +| vm-01-09 | Speed limits | | +| vm-01-10 | Centerline | | +| vm-01-11 | Centerline connection (1) | | +| vm-01-12 | Centerline connection (2) | | +| vm-01-13 | Roads with no centerline (1) | | +| vm-01-14 | Roads with no centerline (2) | | +| vm-01-15 | Road shoulder | | +| vm-01-16 | Road shoulder Linestring sharing | | +| vm-01-17 | Side strip | | +| vm-01-18 | Side strip Linestring sharing | | +| vm-01-19 | Walkway | | +| vm-02-01 | Stop line alignment | | +| vm-02-02 | Stop sign | | +| vm-03-01 | Intersection criteria | | +| vm-03-02 | Lanelet's turn direction and virtual | | +| vm-03-03 | Lanelet width in the intersection | | +| vm-03-04 | Lanelet creation in the intersection | | +| vm-03-05 | Lanelet division in the intersection | | +| vm-03-06 | Guide lines in the intersection | | +| vm-03-07 | Multiple lanelets in the intersection | | +| vm-03-08 | Intersection Area range | | +| vm-03-09 | Range of Lanelet in the intersection | | +| vm-03-10 | Right of way (with signal) | | +| vm-03-11 | Right of way (without signal) | | +| vm-03-12 | Right of way supplements | | +| vm-03-13 | Merging from private area, sidewalk | | +| vm-03-14 | Road marking | | +| vm-03-15 | Exclusive bicycle lane | | | vm-04-01 | Traffic light basics | [mapping.traffic_light.missing_regulatory_elements](./docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md), [mapping.traffic_light.regulatory_element_details](./docs/traffic_light/regulatory_element_details_for_traffic_lights.md) (Undone) | -| vm-04-02 | Traffic light position and size | | -| vm-04-03 | Traffic light lamps | | -| vm-05-01 | Crosswalks across the road | [mapping.crosswalk.missing_regulatory_elements](./docs/crosswalk/missing_regulatory_elements_for_crosswalk.md), [mapping.crosswalk.regulatory_element_details](./docs/crosswalk/regulatory_element_details_for_crosswalks.md) | -| vm-05-02 | Crosswalks with pedestrian signals | | -| vm-05-03 | Deceleration for safety at crosswalks | | -| vm-05-04 | Fences | | -| vm-06-01 | Buffer Zone | | -| vm-06-02 | No parking signs | | -| vm-06-03 | No stopping signs | | -| vm-06-04 | No stopping sections | | -| vm-06-05 | Detection area | | -| vm-07-01 | Vector Map creation range | | -| vm-07-02 | Range of detecting pedestrians who enter the road | | -| vm-07-03 | Guardrails, guard pipes, fences | | -| vm-07-04 | Ellipsoidal height | | +| vm-04-02 | Traffic light position and size | | +| vm-04-03 | Traffic light lamps | | +| vm-05-01 | Crosswalks across the road | [mapping.crosswalk.missing_regulatory_elements](./docs/crosswalk/missing_regulatory_elements_for_crosswalk.md), [mapping.crosswalk.regulatory_element_details](./docs/crosswalk/regulatory_element_details_for_crosswalks.md) | +| vm-05-02 | Crosswalks with pedestrian signals | | +| vm-05-03 | Deceleration for safety at crosswalks | | +| vm-05-04 | Fences | | +| vm-06-01 | Buffer Zone | | +| vm-06-02 | No parking signs | | +| vm-06-03 | No stopping signs | | +| vm-06-04 | No stopping sections | | +| vm-06-05 | Detection area | | +| vm-07-01 | Vector Map creation range | | +| vm-07-02 | Range of detecting pedestrians who enter the road | | +| vm-07-03 | Guardrails, guard pipes, fences | | +| vm-07-04 | Ellipsoidal height | | diff --git a/map/autoware_lanelet2_map_validator/docs/crosswalk/missing_regulatory_elements_for_crosswalk.md b/map/autoware_lanelet2_map_validator/docs/crosswalk/missing_regulatory_elements_for_crosswalk.md index e07210d3..381d8bd4 100644 --- a/map/autoware_lanelet2_map_validator/docs/crosswalk/missing_regulatory_elements_for_crosswalk.md +++ b/map/autoware_lanelet2_map_validator/docs/crosswalk/missing_regulatory_elements_for_crosswalk.md @@ -9,9 +9,9 @@ mapping.crosswalk.missing_regulatory_elements This validator checks whether each `crosswalk` subtype lanelet has a relavant regulatory element. The issue specifies the crosswalk "lanelet" as the **primitive**, and the lanelet ID will be specified as the **ID**. -| Message | Severity | Description | -| ------- | -------- | ----------- | -| "No regulatory element refers to this crosswalk." | Error | There is a `crosswalk` subtype lanelet that hasn't been referred to any regulatory element. | +| Message | Severity | Description | +| ------------------------------------------------- | -------- | ------------------------------------------------------------------------------------------- | +| "No regulatory element refers to this crosswalk." | Error | There is a `crosswalk` subtype lanelet that hasn't been referred to any regulatory element. | ## Related source codes diff --git a/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md b/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md index 8d423b00..4215d4df 100644 --- a/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md +++ b/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md @@ -11,16 +11,16 @@ This validator checks seven types of issues. All output issues specify the crosswalk "regulatory element" as the **primitive**, and the lanelet ID will be specified as the **ID**. -| Message | Severity | Description | -| ------- | -------- | ----------- | -| "Refers of crosswalk regulatory element must have type of crosswalk." | Error | There is a `crosswalk` subtype regulatory element whose `refers` is not a `crosswalk` subtype lanelet. | -| "Refline of crosswalk regulatory element must have type of stopline." | Error | There is a `crosswalk` subtype regulatory element whose `ref_line` is not a `stop_line` type linestring. | -| "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon." | Error | There is a `crosswalk` subtype regulatory element whose `crosswalk_polygon` is not a `crosswalk_polygon` type polygon. | -| "Regulatory element of cross walk must have lanelet of crosswalk(refers)." | Error | There is a `crosswalk` subtype regulatory element that has no `refers`es. | -| "Regulatory element of cross walk must have only one lanelet of crosswalk(refers)." | Error | There is a `crosswalk` subtype regulatory element that has multiple `refers`es. | -| "Regulatory element of cross walk does not have stop line(ref_line)." | Info | There is a `crosswalk` subtype regulatory element that has no `ref_line`s | -| "Regulatory element of cross walk is nice to have crosswalk_polygon." | Warning | There is a `crosswalk` subtype regulatory element that has no `crosswalk_polygon`s. | -| "Regulatory element of cross walk must have only one crosswalk_polygon." | Error | There is a `crosswalk` subtype regulatory element that has multiple `crosswalk_polygon`s. | +| Message | Severity | Description | +| ---------------------------------------------------------------------------------------- | -------- | ---------------------------------------------------------------------------------------------------------------------- | +| "Refers of crosswalk regulatory element must have type of crosswalk." | Error | There is a `crosswalk` subtype regulatory element whose `refers` is not a `crosswalk` subtype lanelet. | +| "Refline of crosswalk regulatory element must have type of stopline." | Error | There is a `crosswalk` subtype regulatory element whose `ref_line` is not a `stop_line` type linestring. | +| "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon." | Error | There is a `crosswalk` subtype regulatory element whose `crosswalk_polygon` is not a `crosswalk_polygon` type polygon. | +| "Regulatory element of cross walk must have lanelet of crosswalk(refers)." | Error | There is a `crosswalk` subtype regulatory element that has no `refers`es. | +| "Regulatory element of cross walk must have only one lanelet of crosswalk(refers)." | Error | There is a `crosswalk` subtype regulatory element that has multiple `refers`es. | +| "Regulatory element of cross walk does not have stop line(ref_line)." | Info | There is a `crosswalk` subtype regulatory element that has no `ref_line`s | +| "Regulatory element of cross walk is nice to have crosswalk_polygon." | Warning | There is a `crosswalk` subtype regulatory element that has no `crosswalk_polygon`s. | +| "Regulatory element of cross walk must have only one crosswalk_polygon." | Error | There is a `crosswalk` subtype regulatory element that has multiple `crosswalk_polygon`s. | ## Related source codes diff --git a/map/autoware_lanelet2_map_validator/docs/stop_line/missing_regulatory_elements_for_stop_lines.md b/map/autoware_lanelet2_map_validator/docs/stop_line/missing_regulatory_elements_for_stop_lines.md index 26a72eec..27b7c20a 100644 --- a/map/autoware_lanelet2_map_validator/docs/stop_line/missing_regulatory_elements_for_stop_lines.md +++ b/map/autoware_lanelet2_map_validator/docs/stop_line/missing_regulatory_elements_for_stop_lines.md @@ -9,9 +9,9 @@ mapping.stop_line.missing_regulatory_elements This validator checks whether each `stop_line` type linestring has a relavant regulatory element. The issue specifies the stop_line "linestring" as the **primitive**, and the lanelet ID will be specified as the **ID**. -| Message | Severity | Description | -| ------- | -------- | ----------- | -| "No regulatory element refers to this stop line." | Error | There is a `stop_line` type linestring that hasn't been referred to any regulatory element. | +| Message | Severity | Description | +| ------------------------------------------------- | -------- | ------------------------------------------------------------------------------------------- | +| "No regulatory element refers to this stop line." | Error | There is a `stop_line` type linestring that hasn't been referred to any regulatory element. | ## Related source codes diff --git a/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md b/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md index 8acf2097..222ef2c5 100644 --- a/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md +++ b/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md @@ -9,9 +9,9 @@ mapping.traffic_light.missing_regulatory_elements This validator checks whether each `traffic_light` type linestring has a relavant regulatory element. The output issue specifies the traffic_light "linestring" as the **primitive**, and the linestring ID will be specified as the **ID**. -| Message | Severity | Description | -| ------- | -------- | ----------- | -| "No regulatory element refers to this traffic light." | Error | There is a `traffic_light` type linestring that hasn't been referred to any regulatory element. | +| Message | Severity | Description | +| ----------------------------------------------------- | -------- | ----------------------------------------------------------------------------------------------- | +| "No regulatory element refers to this traffic light." | Error | There is a `traffic_light` type linestring that hasn't been referred to any regulatory element. | ## Related source codes diff --git a/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md b/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md index dfa58c28..5c117133 100644 --- a/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md +++ b/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md @@ -11,12 +11,12 @@ This validator checks four types of issues. All output issues specify the traffic_light "regulatory element" as the **primitive**, and the linestring ID will be specified as the **ID**. -| Message | Severity | Description | -| ------- | -------- | ----------- | -| "Refers of traffic light regulatory element must have type of traffic_light." | Error | There is a `traffic_light` subtype regulatory element whose `refers` is not a `traffic_light` type linestring. | -| "Refline of traffic light regulatory element must have type of stop_line." | Error | There is a `traffic_light` subtype regulatory element whose `ref_line` is not a `stop_line` type linestring. | -| "Regulatory element of traffic light must have a traffic light(refers)." | Error | There is a `traffic_light` subtype regulatory element that has no `refers`es. | -| "Regulatory element of traffic light must have a stop line(ref_line)." | Error | There is a `traffic_light` subtype regulatory element that has no `ref_line`s | +| Message | Severity | Description | +| ----------------------------------------------------------------------------- | -------- | -------------------------------------------------------------------------------------------------------------- | +| "Refers of traffic light regulatory element must have type of traffic_light." | Error | There is a `traffic_light` subtype regulatory element whose `refers` is not a `traffic_light` type linestring. | +| "Refline of traffic light regulatory element must have type of stop_line." | Error | There is a `traffic_light` subtype regulatory element whose `ref_line` is not a `stop_line` type linestring. | +| "Regulatory element of traffic light must have a traffic light(refers)." | Error | There is a `traffic_light` subtype regulatory element that has no `refers`es. | +| "Regulatory element of traffic light must have a stop line(ref_line)." | Error | There is a `traffic_light` subtype regulatory element that has no `ref_line`s | ## Related source codes diff --git a/map/autoware_lanelet2_map_validator/package.xml b/map/autoware_lanelet2_map_validator/package.xml index ac0d12eb..270c454b 100644 --- a/map/autoware_lanelet2_map_validator/package.xml +++ b/map/autoware_lanelet2_map_validator/package.xml @@ -20,7 +20,6 @@ lanelet2_validation yaml-cpp - ament_cmake_ros diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp index 9a629146..82a13c48 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp @@ -61,31 +61,34 @@ RegulatoryElementsDetailsForCrosswalksValidator::checkRegulatoryElementOfCrosswa auto crosswalk_polygons = elem->getParameters( lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon); - // If this is a crosswalk type regulatory element, the "refers" has to be a "crosswalk" subtype lanelet - const auto & issue_cw = lanelet::validation::Issue( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::Lanelet, - lanelet::utils::getId(), - "Refers of crosswalk regulatory element must have type of crosswalk."); - lanelet::autoware::validation::checkPrimitivesType( - refers, lanelet::AttributeValueString::Lanelet, lanelet::AttributeValueString::Crosswalk, - issue_cw, issues); + // If this is a crosswalk type regulatory element, the "refers" has to be a "crosswalk" subtype + // lanelet + const auto & issue_cw = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::Lanelet, + lanelet::utils::getId(), + "Refers of crosswalk regulatory element must have type of crosswalk."); + lanelet::autoware::validation::checkPrimitivesType( + refers, lanelet::AttributeValueString::Lanelet, lanelet::AttributeValueString::Crosswalk, + issue_cw, issues); - // If this is a crosswalk type regulatory element, the "ref_line" has to be a "stop_line" type linestring - const auto & issue_sl = lanelet::validation::Issue( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, - lanelet::utils::getId(), - "Refline of crosswalk regulatory element must have type of stopline."); - lanelet::autoware::validation::checkPrimitivesType( - ref_lines, lanelet::AttributeValueString::StopLine, issue_sl, issues); + // If this is a crosswalk type regulatory element, the "ref_line" has to be a "stop_line" type + // linestring + const auto & issue_sl = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, + lanelet::utils::getId(), + "Refline of crosswalk regulatory element must have type of stopline."); + lanelet::autoware::validation::checkPrimitivesType( + ref_lines, lanelet::AttributeValueString::StopLine, issue_sl, issues); - // If this is a crosswalk type regulatory element, the "crosswalk_polygon" has to be a "crosswalk_polygon" type polygon - const auto & issue_poly = lanelet::validation::Issue( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::Polygon, - lanelet::utils::getId(), - "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon."); - lanelet::autoware::validation::checkPrimitivesType( - crosswalk_polygons, lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon, - issue_poly, issues); + // If this is a crosswalk type regulatory element, the "crosswalk_polygon" has to be a + // "crosswalk_polygon" type polygon + const auto & issue_poly = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::Polygon, + lanelet::utils::getId(), + "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon."); + lanelet::autoware::validation::checkPrimitivesType( + crosswalk_polygons, lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon, + issue_poly, issues); // Report warning if regulatory element does not have crosswalk polygon if (crosswalk_polygons.empty()) { From fcbc7d83681fa568d96aec5f0a4feeaff2bfed76 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Mon, 30 Sep 2024 12:59:20 +0900 Subject: [PATCH 16/45] Fixed long to uint64_t Signed-off-by: TaikiYamada4 --- map/autoware_lanelet2_map_validator/src/main.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/src/main.cpp b/map/autoware_lanelet2_map_validator/src/main.cpp index b8e8be7d..2c208ed3 100644 --- a/map/autoware_lanelet2_map_validator/src/main.cpp +++ b/map/autoware_lanelet2_map_validator/src/main.cpp @@ -35,8 +35,8 @@ int process_requirements( YAML::Node yaml_config, const lanelet::autoware::validation::MetaConfig & validator_config) { - unsigned long warning_count = 0; - unsigned long error_count = 0; + uint64_t warning_count = 0; + uint64_t error_count = 0; lanelet::autoware::validation::MetaConfig temp_validator_config = validator_config; for (YAML::Node requirement : yaml_config["requirements"]) { From 1685e7e196c64564a0d4465977e9863a0bd1fe1d Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Mon, 30 Sep 2024 13:50:55 +0900 Subject: [PATCH 17/45] Fixed spelling Signed-off-by: TaikiYamada4 --- map/autoware_lanelet2_map_validator/README.md | 10 +++++----- .../missing_regulatory_elements_for_crosswalk.md | 2 +- .../regulatory_element_details_for_crosswalks.md | 2 +- .../missing_regulatory_elements_for_stop_lines.md | 2 +- .../missing_regulatory_elements_for_traffic_lights.md | 2 +- .../regulatory_element_details_for_traffic_lights.md | 2 +- map/autoware_lanelet2_map_validator/src/lib/cli.cpp | 8 ++++---- .../regulatory_element_details_for_crosswalks.cpp | 2 +- .../missing_regulatory_elements_for_stop_lines.cpp | 2 +- .../regulatory_element_details_for_traffic_lights.cpp | 2 +- map/autoware_lanelet2_map_validator/src/main.cpp | 6 +++--- .../test/src/test_missing_regulatory_elements.cpp | 2 +- .../test/src/test_regulatory_element_details.cpp | 8 ++++---- 13 files changed, 25 insertions(+), 25 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/README.md b/map/autoware_lanelet2_map_validator/README.md index bb346a49..f7aa2102 100644 --- a/map/autoware_lanelet2_map_validator/README.md +++ b/map/autoware_lanelet2_map_validator/README.md @@ -71,7 +71,7 @@ Then, the `autoware_lanelet2_map_validator` will scan through the input yaml fil ros2 run autoware_lanelet2_map_validator autoware_lanelet2_map_validator --input_requirements autoware_requirements_set.yaml --output_directory ./ ``` -When the `input_requirements` is thown to `autoware_lanelet2_map_validator`, it will output a `lanelet2_validation_results.yaml` file which looks like the following. +When the `input_requirements` is thrown to `autoware_lanelet2_map_validator`, it will output a `lanelet2_validation_results.yaml` file which looks like the following. ```yaml requirements: @@ -139,16 +139,16 @@ requirements: | option | description | | -------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | | `-h, --help` | Explains about this tool and show a list of options | -| `--print` | Only print all avalible checker, but dont run them | +| `--print` | Print all available checker without running them | | `-m, --map_file` | Path to the map to be validated | | `-i, --input_requirements` | Path to the yaml file where the list of requirements and validations is written | | `-o, --output_directory` | Directory to save the list of validation results in a yaml format | -| `-v, --validator` | 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 | +| `-v, --validator` | Comma separated list of regexes to filter the applicable validators. Will run all validators by default. Example: `mapping.*` to run all checks for the mapping | | `-p, --projector` | Projector used for loading lanelet map. Available projectors are: mgrs, utm, transverse_mercator. (default: mgrs) | -| `-l, --location` | Location of the map (for instanciating the traffic rules), e.g. de for Germany | +| `-l, --location` | Location of the map (for instantiating the traffic rules), e.g. de for Germany | | `--participants` | Participants for which the routing graph will be instanciated (default: vehicle) | | `--lat` | latitude coordinate of map origin. This is required for the transverse mercator and utm projector. | -| `--lon` | longitude coofdinate of map origin. This is required for the transverse mercator and utm projector. | +| `--lon` | longitude coordinate of map origin. This is required for the transverse mercator and utm projector. | ### Available validators diff --git a/map/autoware_lanelet2_map_validator/docs/crosswalk/missing_regulatory_elements_for_crosswalk.md b/map/autoware_lanelet2_map_validator/docs/crosswalk/missing_regulatory_elements_for_crosswalk.md index 381d8bd4..43ff4327 100644 --- a/map/autoware_lanelet2_map_validator/docs/crosswalk/missing_regulatory_elements_for_crosswalk.md +++ b/map/autoware_lanelet2_map_validator/docs/crosswalk/missing_regulatory_elements_for_crosswalk.md @@ -6,7 +6,7 @@ mapping.crosswalk.missing_regulatory_elements ## Feature -This validator checks whether each `crosswalk` subtype lanelet has a relavant regulatory element. +This validator checks whether each `crosswalk` subtype lanelet has a relevant regulatory element. The issue specifies the crosswalk "lanelet" as the **primitive**, and the lanelet ID will be specified as the **ID**. | Message | Severity | Description | diff --git a/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md b/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md index 4215d4df..53605343 100644 --- a/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md +++ b/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md @@ -14,7 +14,7 @@ All output issues specify the crosswalk "regulatory element" as the **primitive* | Message | Severity | Description | | ---------------------------------------------------------------------------------------- | -------- | ---------------------------------------------------------------------------------------------------------------------- | | "Refers of crosswalk regulatory element must have type of crosswalk." | Error | There is a `crosswalk` subtype regulatory element whose `refers` is not a `crosswalk` subtype lanelet. | -| "Refline of crosswalk regulatory element must have type of stopline." | Error | There is a `crosswalk` subtype regulatory element whose `ref_line` is not a `stop_line` type linestring. | +| "ref_line of crosswalk regulatory element must have type of stopline." | Error | There is a `crosswalk` subtype regulatory element whose `ref_line` is not a `stop_line` type linestring. | | "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon." | Error | There is a `crosswalk` subtype regulatory element whose `crosswalk_polygon` is not a `crosswalk_polygon` type polygon. | | "Regulatory element of cross walk must have lanelet of crosswalk(refers)." | Error | There is a `crosswalk` subtype regulatory element that has no `refers`es. | | "Regulatory element of cross walk must have only one lanelet of crosswalk(refers)." | Error | There is a `crosswalk` subtype regulatory element that has multiple `refers`es. | diff --git a/map/autoware_lanelet2_map_validator/docs/stop_line/missing_regulatory_elements_for_stop_lines.md b/map/autoware_lanelet2_map_validator/docs/stop_line/missing_regulatory_elements_for_stop_lines.md index 27b7c20a..865624a6 100644 --- a/map/autoware_lanelet2_map_validator/docs/stop_line/missing_regulatory_elements_for_stop_lines.md +++ b/map/autoware_lanelet2_map_validator/docs/stop_line/missing_regulatory_elements_for_stop_lines.md @@ -6,7 +6,7 @@ mapping.stop_line.missing_regulatory_elements ## Feature -This validator checks whether each `stop_line` type linestring has a relavant regulatory element. +This validator checks whether each `stop_line` type linestring has a relevant regulatory element. The issue specifies the stop_line "linestring" as the **primitive**, and the lanelet ID will be specified as the **ID**. | Message | Severity | Description | diff --git a/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md b/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md index 222ef2c5..95b576c8 100644 --- a/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md +++ b/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md @@ -6,7 +6,7 @@ mapping.traffic_light.missing_regulatory_elements ## Feature -This validator checks whether each `traffic_light` type linestring has a relavant regulatory element. +This validator checks whether each `traffic_light` type linestring has a relevant regulatory element. The output issue specifies the traffic_light "linestring" as the **primitive**, and the linestring ID will be specified as the **ID**. | Message | Severity | Description | diff --git a/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md b/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md index 5c117133..7257a822 100644 --- a/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md +++ b/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md @@ -14,7 +14,7 @@ All output issues specify the traffic_light "regulatory element" as the **primit | Message | Severity | Description | | ----------------------------------------------------------------------------- | -------- | -------------------------------------------------------------------------------------------------------------- | | "Refers of traffic light regulatory element must have type of traffic_light." | Error | There is a `traffic_light` subtype regulatory element whose `refers` is not a `traffic_light` type linestring. | -| "Refline of traffic light regulatory element must have type of stop_line." | Error | There is a `traffic_light` subtype regulatory element whose `ref_line` is not a `stop_line` type linestring. | +| "ref_line of traffic light regulatory element must have type of stop_line." | Error | There is a `traffic_light` subtype regulatory element whose `ref_line` is not a `stop_line` type linestring. | | "Regulatory element of traffic light must have a traffic light(refers)." | Error | There is a `traffic_light` subtype regulatory element that has no `refers`es. | | "Regulatory element of traffic light must have a stop line(ref_line)." | Error | There is a `traffic_light` subtype regulatory element that has no `ref_line`s | diff --git a/map/autoware_lanelet2_map_validator/src/lib/cli.cpp b/map/autoware_lanelet2_map_validator/src/lib/cli.cpp index 66622b29..cac19002 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/cli.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/cli.cpp @@ -52,7 +52,7 @@ MetaConfig parseCommandLine(int argc, const char * argv[]) ("location,l", po::value(&validation_config.location)->default_value(validation_config.location), - "Location of the map (for instanciating 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 instanciated (default: vehicle)") @@ -60,18 +60,18 @@ MetaConfig parseCommandLine(int argc, const char * argv[]) ("lat", po::value(&validation_config.origin.lat) ->default_value(validation_config.origin.lat), - "latitude coordinate of map origin. This is reguired for the transverse " + "latitude coordinate of map origin. This is required for the transverse " "mercator " "and utm projector.") ("lon", po::value(&validation_config.origin.lon) ->default_value(validation_config.origin.lon), - "longitude coofdinate of map origin. This is reguired for the transverse " + "longitude coordinate of map origin. This is required for the transverse " "mercator " "and utm projector.") - ("print", "Only print all avalible checker, but dont run them"); + ("print", "Print all available checker without running them"); po::variables_map vm; po::positional_options_description pos; pos.add("map_file", 1); diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp index 82a13c48..6437242b 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp @@ -76,7 +76,7 @@ RegulatoryElementsDetailsForCrosswalksValidator::checkRegulatoryElementOfCrosswa const auto & issue_sl = lanelet::validation::Issue( lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, lanelet::utils::getId(), - "Refline of crosswalk regulatory element must have type of stopline."); + "ref_line of crosswalk regulatory element must have type of stopline."); lanelet::autoware::validation::checkPrimitivesType( ref_lines, lanelet::AttributeValueString::StopLine, issue_sl, issues); diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp index 4c1c6958..31010c1c 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp @@ -57,7 +57,7 @@ MissingRegulatoryElementsForStopLinesValidator::checkMissingRegulatoryElementsFo ranges::views::transform([](auto && ls) { return ls.id(); }) | ranges::views::unique; - // Filter regulatory elements whose refline type is stop line + // Filter regulatory elements whose ref_line type is stop line auto reg_elem_sl = map.regulatoryElementLayer | ranges::views::filter([](auto && elem) { const auto & params = elem->getParameters(); return params.find(lanelet::RoleNameString::RefLine) != params.end(); diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp b/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp index 43be70ec..9fcc0bb2 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp @@ -80,7 +80,7 @@ RegulatoryElementsDetailsForTrafficLightsValidator::checkRegulatoryElementOfTraf const auto & issue_sl = lanelet::validation::Issue( lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, lanelet::utils::getId(), - "Refline of traffic light regulatory element must have type of stop_line."); + "ref_line of traffic light regulatory element must have type of stop_line."); lanelet::autoware::validation::checkPrimitivesType( ref_lines, lanelet::AttributeValueString::StopLine, issue_sl, issues); diff --git a/map/autoware_lanelet2_map_validator/src/main.cpp b/map/autoware_lanelet2_map_validator/src/main.cpp index 2c208ed3..2df30303 100644 --- a/map/autoware_lanelet2_map_validator/src/main.cpp +++ b/map/autoware_lanelet2_map_validator/src/main.cpp @@ -123,8 +123,8 @@ int process_requirements( if (!validator_config.output_file_path.empty()) { std::string file_name = validator_config.output_file_path + "/lanelet2_validation_results.yaml"; - std::ofstream fout(file_name); - fout << yaml_config; + std::ofstream output_file(file_name); + output_file << yaml_config; std::cout << "Results are output to " << file_name << std::endl; } @@ -145,7 +145,7 @@ int main(int argc, char * argv[]) // Print available validators if (config.command_line_config.print) { auto checks = - lanelet::validation::availabeChecks(config.command_line_config.validationConfig.checksFilter); + lanelet::validation::availabeChecks(config.command_line_config.validationConfig.checksFilter); // cspell:disable-line if (checks.empty()) { std::cout << "No checks found matching '" << config.command_line_config.validationConfig.checksFilter << "'\n"; diff --git a/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp index d85a3a5d..c5404afc 100644 --- a/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp +++ b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp @@ -146,7 +146,7 @@ TEST_F(TestSuite, ValidatorAvailability) // NOLINT for gtest "mapping.traffic_light.missing_regulatory_elements"; lanelet::validation::Strings validators = - lanelet::validation::availabeChecks(expected_validators_concat); + lanelet::validation::availabeChecks(expected_validators_concat); // cspell:disable-line uint8_t expected_num_validators = 3; std::cout << "size: " << validators.size() << std::endl; EXPECT_EQ(expected_num_validators, validators.size()); diff --git a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp index 0f1162b9..c6ed6d64 100644 --- a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp +++ b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp @@ -144,7 +144,7 @@ TEST_F(TestSuite, ValidatorAvailability) // NOLINT for gtest "mapping.traffic_light.regulatory_element_details"; lanelet::validation::Strings validators = - lanelet::validation::availabeChecks(expected_validators_concat); + lanelet::validation::availabeChecks(expected_validators_concat); // cspell:disable-line uint8_t expected_num_validators = 2; std::cout << "size: " << validators.size() << std::endl; EXPECT_EQ(expected_num_validators, validators.size()); @@ -164,7 +164,7 @@ TEST_F(TestSuite, ValidatorAvailability) // NOLINT for gtest } } -TEST_F(TestSuite, RegulatoryElementofTrafficLightWithoutTrafficLight) // NOLINT for gtest +TEST_F(TestSuite, RegulatoryElementOfTrafficLightWithoutTrafficLight) // NOLINT for gtest { // Check regulatory element of traffic light without traffic light @@ -205,7 +205,7 @@ TEST_F(TestSuite, RegulatoryElementofTrafficLightWithoutTrafficLight) // NOLINT } } -TEST_F(TestSuite, RegulatoryElementofTrafficLightWithoutStopLine) // NOLINT for gtest +TEST_F(TestSuite, RegulatoryElementOfTrafficLightWithoutStopLine) // NOLINT for gtest { // Check regulatory element of traffic light without stop line @@ -226,7 +226,7 @@ TEST_F(TestSuite, RegulatoryElementofTrafficLightWithoutStopLine) // NOLINT for uint8_t expected_num_issues = 2; static constexpr const char * expected_message1 = - "Refline of traffic light regulatory element must have type of stop_line."; + "ref_line of traffic light regulatory element must have type of stop_line."; static constexpr const char * expected_message2 = "Regulatory element of traffic light must have a stop line(ref_line)."; EXPECT_EQ(expected_num_issues, issues.size()); From 077e7e60a50a55f98c5735a95a1732e5eb43923d Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 30 Sep 2024 04:51:37 +0000 Subject: [PATCH 18/45] style(pre-commit): autofix --- map/autoware_lanelet2_map_validator/README.md | 24 +++++++++---------- ...gulatory_element_details_for_crosswalks.md | 2 +- ...tory_element_details_for_traffic_lights.md | 2 +- .../src/main.cpp | 4 ++-- .../src/test_missing_regulatory_elements.cpp | 2 +- .../src/test_regulatory_element_details.cpp | 2 +- 6 files changed, 18 insertions(+), 18 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/README.md b/map/autoware_lanelet2_map_validator/README.md index f7aa2102..63723c96 100644 --- a/map/autoware_lanelet2_map_validator/README.md +++ b/map/autoware_lanelet2_map_validator/README.md @@ -136,19 +136,19 @@ requirements: ### Available command options -| option | description | -| -------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| `-h, --help` | Explains about this tool and show a list of options | -| `--print` | Print all available checker without running them | -| `-m, --map_file` | Path to the map to be validated | -| `-i, --input_requirements` | Path to the yaml file where the list of requirements and validations is written | -| `-o, --output_directory` | Directory to save the list of validation results in a yaml format | +| option | description | +| -------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| `-h, --help` | Explains about this tool and show a list of options | +| `--print` | Print all available checker without running them | +| `-m, --map_file` | Path to the map to be validated | +| `-i, --input_requirements` | Path to the yaml file where the list of requirements and validations is written | +| `-o, --output_directory` | Directory to save the list of validation results in a yaml format | | `-v, --validator` | Comma separated list of regexes to filter the applicable validators. Will run all validators by default. Example: `mapping.*` to run all checks for the mapping | -| `-p, --projector` | Projector used for loading lanelet map. Available projectors are: mgrs, utm, transverse_mercator. (default: mgrs) | -| `-l, --location` | Location of the map (for instantiating the traffic rules), e.g. de for Germany | -| `--participants` | Participants for which the routing graph will be instanciated (default: vehicle) | -| `--lat` | latitude coordinate of map origin. This is required for the transverse mercator and utm projector. | -| `--lon` | longitude coordinate of map origin. This is required for the transverse mercator and utm projector. | +| `-p, --projector` | Projector used for loading lanelet map. Available projectors are: mgrs, utm, transverse_mercator. (default: mgrs) | +| `-l, --location` | Location of the map (for instantiating the traffic rules), e.g. de for Germany | +| `--participants` | Participants for which the routing graph will be instanciated (default: vehicle) | +| `--lat` | latitude coordinate of map origin. This is required for the transverse mercator and utm projector. | +| `--lon` | longitude coordinate of map origin. This is required for the transverse mercator and utm projector. | ### Available validators diff --git a/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md b/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md index 53605343..f275ce75 100644 --- a/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md +++ b/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md @@ -14,7 +14,7 @@ All output issues specify the crosswalk "regulatory element" as the **primitive* | Message | Severity | Description | | ---------------------------------------------------------------------------------------- | -------- | ---------------------------------------------------------------------------------------------------------------------- | | "Refers of crosswalk regulatory element must have type of crosswalk." | Error | There is a `crosswalk` subtype regulatory element whose `refers` is not a `crosswalk` subtype lanelet. | -| "ref_line of crosswalk regulatory element must have type of stopline." | Error | There is a `crosswalk` subtype regulatory element whose `ref_line` is not a `stop_line` type linestring. | +| "ref_line of crosswalk regulatory element must have type of stopline." | Error | There is a `crosswalk` subtype regulatory element whose `ref_line` is not a `stop_line` type linestring. | | "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon." | Error | There is a `crosswalk` subtype regulatory element whose `crosswalk_polygon` is not a `crosswalk_polygon` type polygon. | | "Regulatory element of cross walk must have lanelet of crosswalk(refers)." | Error | There is a `crosswalk` subtype regulatory element that has no `refers`es. | | "Regulatory element of cross walk must have only one lanelet of crosswalk(refers)." | Error | There is a `crosswalk` subtype regulatory element that has multiple `refers`es. | diff --git a/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md b/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md index 7257a822..ed0dedb4 100644 --- a/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md +++ b/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md @@ -14,7 +14,7 @@ All output issues specify the traffic_light "regulatory element" as the **primit | Message | Severity | Description | | ----------------------------------------------------------------------------- | -------- | -------------------------------------------------------------------------------------------------------------- | | "Refers of traffic light regulatory element must have type of traffic_light." | Error | There is a `traffic_light` subtype regulatory element whose `refers` is not a `traffic_light` type linestring. | -| "ref_line of traffic light regulatory element must have type of stop_line." | Error | There is a `traffic_light` subtype regulatory element whose `ref_line` is not a `stop_line` type linestring. | +| "ref_line of traffic light regulatory element must have type of stop_line." | Error | There is a `traffic_light` subtype regulatory element whose `ref_line` is not a `stop_line` type linestring. | | "Regulatory element of traffic light must have a traffic light(refers)." | Error | There is a `traffic_light` subtype regulatory element that has no `refers`es. | | "Regulatory element of traffic light must have a stop line(ref_line)." | Error | There is a `traffic_light` subtype regulatory element that has no `ref_line`s | diff --git a/map/autoware_lanelet2_map_validator/src/main.cpp b/map/autoware_lanelet2_map_validator/src/main.cpp index 2df30303..5f22b429 100644 --- a/map/autoware_lanelet2_map_validator/src/main.cpp +++ b/map/autoware_lanelet2_map_validator/src/main.cpp @@ -144,8 +144,8 @@ int main(int argc, char * argv[]) // Print available validators if (config.command_line_config.print) { - auto checks = - lanelet::validation::availabeChecks(config.command_line_config.validationConfig.checksFilter); // cspell:disable-line + auto checks = lanelet::validation::availabeChecks( + config.command_line_config.validationConfig.checksFilter); // cspell:disable-line if (checks.empty()) { std::cout << "No checks found matching '" << config.command_line_config.validationConfig.checksFilter << "'\n"; diff --git a/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp index c5404afc..f5604a98 100644 --- a/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp +++ b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp @@ -146,7 +146,7 @@ TEST_F(TestSuite, ValidatorAvailability) // NOLINT for gtest "mapping.traffic_light.missing_regulatory_elements"; lanelet::validation::Strings validators = - lanelet::validation::availabeChecks(expected_validators_concat); // cspell:disable-line + lanelet::validation::availabeChecks(expected_validators_concat); // cspell:disable-line uint8_t expected_num_validators = 3; std::cout << "size: " << validators.size() << std::endl; EXPECT_EQ(expected_num_validators, validators.size()); diff --git a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp index c6ed6d64..1da7ca5a 100644 --- a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp +++ b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp @@ -144,7 +144,7 @@ TEST_F(TestSuite, ValidatorAvailability) // NOLINT for gtest "mapping.traffic_light.regulatory_element_details"; lanelet::validation::Strings validators = - lanelet::validation::availabeChecks(expected_validators_concat); // cspell:disable-line + lanelet::validation::availabeChecks(expected_validators_concat); // cspell:disable-line uint8_t expected_num_validators = 2; std::cout << "size: " << validators.size() << std::endl; EXPECT_EQ(expected_num_validators, validators.size()); From 18524beafe6f9f8680e888e5216cdb4c89a29cbf Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Mon, 30 Sep 2024 14:00:31 +0900 Subject: [PATCH 19/45] Fixed typo Signed-off-by: TaikiYamada4 --- map/autoware_lanelet2_map_validator/README.md | 10 +++++----- map/autoware_lanelet2_map_validator/src/lib/cli.cpp | 2 +- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/README.md b/map/autoware_lanelet2_map_validator/README.md index 63723c96..75206154 100644 --- a/map/autoware_lanelet2_map_validator/README.md +++ b/map/autoware_lanelet2_map_validator/README.md @@ -144,11 +144,11 @@ requirements: | `-i, --input_requirements` | Path to the yaml file where the list of requirements and validations is written | | `-o, --output_directory` | Directory to save the list of validation results in a yaml format | | `-v, --validator` | Comma separated list of regexes to filter the applicable validators. Will run all validators by default. Example: `mapping.*` to run all checks for the mapping | -| `-p, --projector` | Projector used for loading lanelet map. Available projectors are: mgrs, utm, transverse_mercator. (default: mgrs) | -| `-l, --location` | Location of the map (for instantiating the traffic rules), e.g. de for Germany | -| `--participants` | Participants for which the routing graph will be instanciated (default: vehicle) | -| `--lat` | latitude coordinate of map origin. This is required for the transverse mercator and utm projector. | -| `--lon` | longitude coordinate of map origin. This is required for the transverse mercator and utm projector. | +| `-p, --projector` | Projector used for loading lanelet map. Available projectors are: mgrs, utm, transverse_mercator. (default: mgrs) | +| `-l, --location` | Location of the map (for instantiating the traffic rules), e.g. de for Germany | +| `--participants` | Participants for which the routing graph will be instantiated (default: vehicle) | +| `--lat` | latitude coordinate of map origin. This is required for the transverse mercator and utm projector. | +| `--lon` | longitude coordinate of map origin. This is required for the transverse mercator and utm projector. | ### Available validators diff --git a/map/autoware_lanelet2_map_validator/src/lib/cli.cpp b/map/autoware_lanelet2_map_validator/src/lib/cli.cpp index cac19002..bb539c2c 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/cli.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/cli.cpp @@ -55,7 +55,7 @@ MetaConfig parseCommandLine(int argc, const char * argv[]) "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 instanciated (default: vehicle)") + "Participants for which the routing graph will be instantiated (default: vehicle)") ("lat", po::value(&validation_config.origin.lat) From dfdb4f0d1f021355b7ae845aedfc380cb05923ca Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Mon, 30 Sep 2024 14:27:02 +0900 Subject: [PATCH 20/45] Split long lines in the code Signed-off-by: TaikiYamada4 --- .../missing_regulatory_elements_for_crosswalks.hpp | 9 ++++++--- .../regulatory_element_details_for_crosswalks.hpp | 9 ++++++--- .../missing_regulatory_elements_for_stop_lines.hpp | 9 ++++++--- .../missing_regulatory_elements_for_traffic_lights.hpp | 9 ++++++--- .../regulatory_element_details_for_traffic_lights.hpp | 9 ++++++--- 5 files changed, 30 insertions(+), 15 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp index 7f4db1ae..d1bb33a4 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp @@ -12,8 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__\ +MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__\ +MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ #include #include @@ -36,4 +38,5 @@ class MissingRegulatoryElementsForCrosswalksValidator : public lanelet::validati } // namespace validation } // namespace lanelet -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__ + // MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp index 1b4f9265..993ce233 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp @@ -12,8 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__\ +REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__\ +REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ #include #include @@ -36,4 +38,5 @@ class RegulatoryElementsDetailsForCrosswalksValidator : public lanelet::validati } // namespace validation } // namespace lanelet -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__ + // REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp index c99add9a..f264339a 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp @@ -12,8 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__STOP_LINE__\ +MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__STOP_LINE__\ +MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ #include #include @@ -36,4 +38,5 @@ class MissingRegulatoryElementsForStopLinesValidator : public lanelet::validatio } // namespace validation } // namespace lanelet -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__STOP_LINE__ + // MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp index e854ef23..aafd3ca6 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp @@ -12,8 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__\ +MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__\ +MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ #include #include @@ -39,4 +41,5 @@ class MissingRegulatoryElementsForTrafficLightsValidator : public lanelet::valid } // namespace validation } // namespace lanelet -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__ + // MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp index d0411fe1..9a24db3e 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp @@ -12,8 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__\ +REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__\ +REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ #include #include @@ -43,4 +45,5 @@ class RegulatoryElementsDetailsForTrafficLightsValidator : public lanelet::valid } // namespace validation } // namespace lanelet -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__ + // REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ From ef092050412760fa6d433df1a3dd1592111e983d Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 30 Sep 2024 05:29:36 +0000 Subject: [PATCH 21/45] style(pre-commit): autofix --- map/autoware_lanelet2_map_validator/README.md | 10 +++++----- .../missing_regulatory_elements_for_crosswalks.hpp | 6 +++--- .../regulatory_element_details_for_crosswalks.hpp | 6 +++--- .../missing_regulatory_elements_for_stop_lines.hpp | 6 +++--- .../missing_regulatory_elements_for_traffic_lights.hpp | 6 +++--- .../regulatory_element_details_for_traffic_lights.hpp | 6 +++--- 6 files changed, 20 insertions(+), 20 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/README.md b/map/autoware_lanelet2_map_validator/README.md index 75206154..ae24d03b 100644 --- a/map/autoware_lanelet2_map_validator/README.md +++ b/map/autoware_lanelet2_map_validator/README.md @@ -144,11 +144,11 @@ requirements: | `-i, --input_requirements` | Path to the yaml file where the list of requirements and validations is written | | `-o, --output_directory` | Directory to save the list of validation results in a yaml format | | `-v, --validator` | Comma separated list of regexes to filter the applicable validators. Will run all validators by default. Example: `mapping.*` to run all checks for the mapping | -| `-p, --projector` | Projector used for loading lanelet map. Available projectors are: mgrs, utm, transverse_mercator. (default: mgrs) | -| `-l, --location` | Location of the map (for instantiating the traffic rules), e.g. de for Germany | -| `--participants` | Participants for which the routing graph will be instantiated (default: vehicle) | -| `--lat` | latitude coordinate of map origin. This is required for the transverse mercator and utm projector. | -| `--lon` | longitude coordinate of map origin. This is required for the transverse mercator and utm projector. | +| `-p, --projector` | Projector used for loading lanelet map. Available projectors are: mgrs, utm, transverse_mercator. (default: mgrs) | +| `-l, --location` | Location of the map (for instantiating the traffic rules), e.g. de for Germany | +| `--participants` | Participants for which the routing graph will be instantiated (default: vehicle) | +| `--lat` | latitude coordinate of map origin. This is required for the transverse mercator and utm projector. | +| `--lon` | longitude coordinate of map origin. This is required for the transverse mercator and utm projector. | ### Available validators diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp index d1bb33a4..1686e4ee 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__\ +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__\ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ #include @@ -38,5 +38,5 @@ class MissingRegulatoryElementsForCrosswalksValidator : public lanelet::validati } // namespace validation } // namespace lanelet -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__ +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ // MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp index 993ce233..ccb93880 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__\ +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__\ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ #include @@ -38,5 +38,5 @@ class RegulatoryElementsDetailsForCrosswalksValidator : public lanelet::validati } // namespace validation } // namespace lanelet -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__ +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ // REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp index f264339a..061e57fe 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__STOP_LINE__\ +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__STOP_LINE__\ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ #include @@ -38,5 +38,5 @@ class MissingRegulatoryElementsForStopLinesValidator : public lanelet::validatio } // namespace validation } // namespace lanelet -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__STOP_LINE__ +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ // MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp index aafd3ca6..d2ea62ed 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__\ +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__\ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ #include @@ -41,5 +41,5 @@ class MissingRegulatoryElementsForTrafficLightsValidator : public lanelet::valid } // namespace validation } // namespace lanelet -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__ +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ // MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp index 9a24db3e..3753897d 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp +++ b/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__\ +#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__\ +#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ #include @@ -45,5 +45,5 @@ class RegulatoryElementsDetailsForTrafficLightsValidator : public lanelet::valid } // namespace validation } // namespace lanelet -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__ +#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ // REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ From 4e429964876abc0e6a06288718a2625fb83c9731 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Mon, 30 Sep 2024 17:08:44 +0900 Subject: [PATCH 22/45] Changed the entire structure. Fixed pre-commit.ci related errors. Signed-off-by: TaikiYamada4 --- map/autoware_lanelet2_map_validator/CMakeLists.txt | 5 +++-- map/autoware_lanelet2_map_validator/src/lib/cli.cpp | 2 +- .../lib}/cli.hpp | 6 +++--- .../lib}/utils.hpp | 6 +++--- .../src/lib/validation.cpp | 5 ++++- .../lib}/validation.hpp | 10 +++++----- map/autoware_lanelet2_map_validator/src/main.cpp | 7 +++---- .../missing_regulatory_elements_for_crosswalk.cpp | 5 +++-- .../missing_regulatory_elements_for_crosswalks.hpp | 9 +++++++++ .../regulatory_element_details_for_crosswalks.cpp | 6 ++++-- .../regulatory_element_details_for_crosswalks.hpp | 9 +++++++++ .../missing_regulatory_elements_for_stop_lines.cpp | 7 +++++-- .../missing_regulatory_elements_for_stop_lines.hpp | 9 +++++++++ ...missing_regulatory_elements_for_traffic_lights.cpp} | 7 +++++-- .../missing_regulatory_elements_for_traffic_lights.hpp | 9 +++++++++ .../regulatory_element_details_for_traffic_lights.cpp | 6 ++++-- .../regulatory_element_details_for_traffic_lights.hpp | 9 +++++++++ .../src/{lib => }/validators/validator_template.cpp | 2 +- .../validators/validator_template.hpp | 6 +++--- .../test/src/test_missing_regulatory_elements.cpp | 7 ++++--- .../test/src/test_regulatory_element_details.cpp | 5 +++-- 21 files changed, 99 insertions(+), 38 deletions(-) rename map/autoware_lanelet2_map_validator/{include/autoware_lanelet2_map_validator => src/lib}/cli.hpp (87%) rename map/autoware_lanelet2_map_validator/{include/autoware_lanelet2_map_validator => src/lib}/utils.hpp (94%) rename map/autoware_lanelet2_map_validator/{include/autoware_lanelet2_map_validator => src/lib}/validation.hpp (82%) rename map/autoware_lanelet2_map_validator/src/{lib => }/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp (95%) rename map/autoware_lanelet2_map_validator/{include/autoware_lanelet2_map_validator => src}/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp (65%) rename map/autoware_lanelet2_map_validator/src/{lib => }/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp (97%) rename map/autoware_lanelet2_map_validator/{include/autoware_lanelet2_map_validator => src}/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp (66%) rename map/autoware_lanelet2_map_validator/src/{lib => }/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp (95%) rename map/autoware_lanelet2_map_validator/{include/autoware_lanelet2_map_validator => src}/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp (65%) rename map/autoware_lanelet2_map_validator/src/{lib/validators/traffic_light/missing_regulatory_elements_for_traffic_light.cpp => validators/traffic_light/missing_regulatory_elements_for_traffic_lights.cpp} (95%) rename map/autoware_lanelet2_map_validator/{include/autoware_lanelet2_map_validator => src}/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp (65%) rename map/autoware_lanelet2_map_validator/src/{lib => }/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp (96%) rename map/autoware_lanelet2_map_validator/{include/autoware_lanelet2_map_validator => src}/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp (66%) rename map/autoware_lanelet2_map_validator/src/{lib => }/validators/validator_template.cpp (92%) rename map/autoware_lanelet2_map_validator/{include/autoware_lanelet2_map_validator => src}/validators/validator_template.hpp (82%) diff --git a/map/autoware_lanelet2_map_validator/CMakeLists.txt b/map/autoware_lanelet2_map_validator/CMakeLists.txt index 2f0c57ab..c0502dd0 100644 --- a/map/autoware_lanelet2_map_validator/CMakeLists.txt +++ b/map/autoware_lanelet2_map_validator/CMakeLists.txt @@ -8,10 +8,10 @@ ament_auto_find_build_dependencies() find_package(yaml-cpp REQUIRED) include_directories( - include + src ) -file(GLOB_RECURSE autoware_lanelet2_map_validator_lib_src src/lib/*.cpp) +file(GLOB_RECURSE autoware_lanelet2_map_validator_lib_src src/*.cpp) ament_auto_add_library(autoware_lanelet2_map_validator_lib SHARED ${autoware_lanelet2_map_validator_lib_src} ) @@ -32,6 +32,7 @@ if(BUILD_TESTING) target_link_libraries( ${VALIDATION_NAME}_test autoware_lanelet2_map_validator_lib + yaml-cpp ) endfunction() diff --git a/map/autoware_lanelet2_map_validator/src/lib/cli.cpp b/map/autoware_lanelet2_map_validator/src/lib/cli.cpp index bb539c2c..b11472b6 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/cli.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/cli.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_lanelet2_map_validator/cli.hpp" +#include "lib/cli.hpp" namespace po = boost::program_options; diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/cli.hpp b/map/autoware_lanelet2_map_validator/src/lib/cli.hpp similarity index 87% rename from map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/cli.hpp rename to map/autoware_lanelet2_map_validator/src/lib/cli.hpp index 6e90868f..ff94469f 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/cli.hpp +++ b/map/autoware_lanelet2_map_validator/src/lib/cli.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__CLI_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__CLI_HPP_ +#ifndef LIB__CLI_HPP_ +#define LIB__CLI_HPP_ #include @@ -42,4 +42,4 @@ MetaConfig parseCommandLine(int argc, const char * argv[]); } // namespace autoware } // namespace lanelet -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__CLI_HPP_ +#endif // LIB__CLI_HPP_ diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/utils.hpp b/map/autoware_lanelet2_map_validator/src/lib/utils.hpp similarity index 94% rename from map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/utils.hpp rename to map/autoware_lanelet2_map_validator/src/lib/utils.hpp index d5e851ed..57a474f1 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/utils.hpp +++ b/map/autoware_lanelet2_map_validator/src/lib/utils.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__UTILS_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__UTILS_HPP_ +#ifndef LIB__UTILS_HPP_ +#define LIB__UTILS_HPP_ #include #include @@ -82,4 +82,4 @@ void checkPrimitivesType( } // namespace autoware } // namespace lanelet -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__UTILS_HPP_ +#endif // LIB__UTILS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/lib/validation.cpp b/map/autoware_lanelet2_map_validator/src/lib/validation.cpp index 3155f103..161cfc36 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validation.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/validation.cpp @@ -12,11 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_lanelet2_map_validator/validation.hpp" +#include "lib/validation.hpp" #include #include +#include +#include + namespace lanelet { namespace autoware diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validation.hpp b/map/autoware_lanelet2_map_validator/src/lib/validation.hpp similarity index 82% rename from map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validation.hpp rename to map/autoware_lanelet2_map_validator/src/lib/validation.hpp index 9bd89649..984b26d8 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validation.hpp +++ b/map/autoware_lanelet2_map_validator/src/lib/validation.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATION_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATION_HPP_ +#ifndef LIB__VALIDATION_HPP_ +#define LIB__VALIDATION_HPP_ -#include "autoware_lanelet2_map_validator/cli.hpp" -#include "autoware_lanelet2_map_validator/utils.hpp" +#include "lib/cli.hpp" +#include "lib/utils.hpp" #include #include @@ -49,4 +49,4 @@ std::vector validateMap(const MetaConfig & } // namespace autoware } // namespace lanelet -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATION_HPP_ +#endif // LIB__VALIDATION_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/main.cpp b/map/autoware_lanelet2_map_validator/src/main.cpp index 5f22b429..07c4b3cc 100644 --- a/map/autoware_lanelet2_map_validator/src/main.cpp +++ b/map/autoware_lanelet2_map_validator/src/main.cpp @@ -13,10 +13,9 @@ // limitations under the License. #include "lanelet2_validation/Validation.h" - -#include -#include -#include +#include "lib/cli.hpp" +#include "lib/utils.hpp" +#include "lib/validation.hpp" #include diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp similarity index 95% rename from map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp rename to map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp index ec2e78a2..898dc9d5 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp @@ -12,8 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include -#include +#include "lib/utils.hpp" +#include "validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp" + #include #include diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp similarity index 65% rename from map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp rename to map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp index 1686e4ee..71b1ec44 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp +++ b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp @@ -12,10 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. +<<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp #ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ #define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ +======= +#ifndef VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ +#define VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ +>>>>>>> 0fe0b37 (Changed the entire structure.):map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp #include #include @@ -38,5 +43,9 @@ class MissingRegulatoryElementsForCrosswalksValidator : public lanelet::validati } // namespace validation } // namespace lanelet +<<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp #endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ // MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ +======= +#endif // VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ +>>>>>>> 0fe0b37 (Changed the entire structure.):map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp similarity index 97% rename from map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp rename to map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp index 6437242b..163f6587 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp @@ -12,9 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "validators/crosswalk/regulatory_element_details_for_crosswalks.hpp" + +#include "lib/utils.hpp" + #include -#include -#include #include #include diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp similarity index 66% rename from map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp rename to map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp index ccb93880..035fb50b 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp +++ b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp @@ -12,10 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. +<<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp #ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ #define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ +======= +#ifndef VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ +#define VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ +>>>>>>> 0fe0b37 (Changed the entire structure.):map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp #include #include @@ -38,5 +43,9 @@ class RegulatoryElementsDetailsForCrosswalksValidator : public lanelet::validati } // namespace validation } // namespace lanelet +<<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp #endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ // REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ +======= +#endif // VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ +>>>>>>> 0fe0b37 (Changed the entire structure.):map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp b/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp similarity index 95% rename from map/autoware_lanelet2_map_validator/src/lib/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp rename to map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp index 31010c1c..2c1b8aca 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp @@ -12,14 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include -#include +#include "validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp" + +#include "lib/utils.hpp" + #include #include #include #include +#include #include namespace lanelet diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp b/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp similarity index 65% rename from map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp rename to map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp index 061e57fe..7adf0859 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp +++ b/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp @@ -12,10 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. +<<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp #ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ #define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ +======= +#ifndef VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ +#define VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ +>>>>>>> 0fe0b37 (Changed the entire structure.):map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp #include #include @@ -38,5 +43,9 @@ class MissingRegulatoryElementsForStopLinesValidator : public lanelet::validatio } // namespace validation } // namespace lanelet +<<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp #endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ // MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ +======= +#endif // VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ +>>>>>>> 0fe0b37 (Changed the entire structure.):map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/missing_regulatory_elements_for_traffic_light.cpp b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.cpp similarity index 95% rename from map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/missing_regulatory_elements_for_traffic_light.cpp rename to map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.cpp index 218085e6..aeedc6fe 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/missing_regulatory_elements_for_traffic_light.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.cpp @@ -12,14 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include -#include +#include "validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp" + +#include "lib/utils.hpp" + #include #include #include #include +#include #include namespace lanelet diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp similarity index 65% rename from map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp rename to map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp index d2ea62ed..058d7068 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp +++ b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp @@ -12,10 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. +<<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp #ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ #define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ +======= +#ifndef VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ +#define VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ +>>>>>>> 0fe0b37 (Changed the entire structure.):map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp #include #include @@ -41,5 +46,9 @@ class MissingRegulatoryElementsForTrafficLightsValidator : public lanelet::valid } // namespace validation } // namespace lanelet +<<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp #endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ // MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ +======= +#endif // VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ +>>>>>>> 0fe0b37 (Changed the entire structure.):map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp similarity index 96% rename from map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp rename to map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp index 9fcc0bb2..99d34989 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp @@ -12,8 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include -#include +#include "validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp" + +#include "lib/utils.hpp" + #include #include diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp similarity index 66% rename from map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp rename to map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp index 3753897d..a54421ba 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp +++ b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp @@ -12,10 +12,15 @@ // See the License for the specific language governing permissions and // limitations under the License. +<<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp #ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ #define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ +======= +#ifndef VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ +#define VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ +>>>>>>> 0fe0b37 (Changed the entire structure.):map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp #include #include @@ -45,5 +50,9 @@ class RegulatoryElementsDetailsForTrafficLightsValidator : public lanelet::valid } // namespace validation } // namespace lanelet +<<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp #endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ // REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ +======= +#endif // VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ +>>>>>>> 0fe0b37 (Changed the entire structure.):map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp diff --git a/map/autoware_lanelet2_map_validator/src/lib/validators/validator_template.cpp b/map/autoware_lanelet2_map_validator/src/validators/validator_template.cpp similarity index 92% rename from map/autoware_lanelet2_map_validator/src/lib/validators/validator_template.cpp rename to map/autoware_lanelet2_map_validator/src/validators/validator_template.cpp index 4eacfbd0..c2a921c1 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validators/validator_template.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/validator_template.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include +#include "validator_template.hpp" namespace lanelet { diff --git a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/validator_template.hpp b/map/autoware_lanelet2_map_validator/src/validators/validator_template.hpp similarity index 82% rename from map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/validator_template.hpp rename to map/autoware_lanelet2_map_validator/src/validators/validator_template.hpp index b9dbb2df..dc09c0ff 100644 --- a/map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/validator_template.hpp +++ b/map/autoware_lanelet2_map_validator/src/validators/validator_template.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__VALIDATOR_TEMPLATE_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__VALIDATOR_TEMPLATE_HPP_ +#ifndef VALIDATORS__VALIDATOR_TEMPLATE_HPP_ +#define VALIDATORS__VALIDATOR_TEMPLATE_HPP_ #include #include @@ -35,4 +35,4 @@ class ValidatorTemplate : public lanelet::validation::MapValidator } // namespace validation } // namespace lanelet -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__VALIDATOR_TEMPLATE_HPP_ +#endif // VALIDATORS__VALIDATOR_TEMPLATE_HPP_ diff --git a/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp index f5604a98..c940d3dc 100644 --- a/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp +++ b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp @@ -12,11 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp" +#include "validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp" +#include "validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp" + #include #include -#include -#include -#include #include #include diff --git a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp index 1da7ca5a..43deee94 100644 --- a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp +++ b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp @@ -12,10 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "validators/crosswalk/regulatory_element_details_for_crosswalks.hpp" +#include "validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp" + #include #include -#include -#include #include #include From f9a16da52f803330ed0f3365399dc60c680f079e Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 30 Sep 2024 08:15:30 +0000 Subject: [PATCH 23/45] style(pre-commit): autofix --- .../crosswalk/missing_regulatory_elements_for_crosswalks.hpp | 4 ++-- .../crosswalk/regulatory_element_details_for_crosswalks.hpp | 4 ++-- .../stop_line/missing_regulatory_elements_for_stop_lines.hpp | 4 ++-- .../missing_regulatory_elements_for_traffic_lights.hpp | 4 ++-- .../regulatory_element_details_for_traffic_lights.hpp | 4 ++-- 5 files changed, 10 insertions(+), 10 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp index 71b1ec44..67c99fb6 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp +++ b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp @@ -13,9 +13,9 @@ // limitations under the License. <<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ +#ifndef VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ +#define VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ ======= #ifndef VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp index 035fb50b..a2afa429 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp +++ b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp @@ -13,9 +13,9 @@ // limitations under the License. <<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ +#ifndef VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ +#define VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ ======= #ifndef VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp b/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp index 7adf0859..39d88fe7 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp +++ b/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp @@ -13,9 +13,9 @@ // limitations under the License. <<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ +#ifndef VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ +#define VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ ======= #ifndef VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp index 058d7068..4f7c9dab 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp +++ b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp @@ -13,9 +13,9 @@ // limitations under the License. <<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ +#ifndef VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ +#define VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ ======= #ifndef VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp index a54421ba..ec5fd9ae 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp +++ b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp @@ -13,9 +13,9 @@ // limitations under the License. <<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp -#ifndef AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ +#ifndef VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ -#define AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ +#define VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ ======= #ifndef VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ From 147ba6a18abc0662bd0950b7ad8c34a70becf0d8 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Mon, 30 Sep 2024 17:18:58 +0900 Subject: [PATCH 24/45] Fixed pre-commit.ci related stuff Signed-off-by: TaikiYamada4 --- map/autoware_lanelet2_map_validator/src/main.cpp | 4 ++-- .../missing_regulatory_elements_for_crosswalks.hpp | 12 ------------ .../regulatory_element_details_for_crosswalks.hpp | 12 ------------ .../missing_regulatory_elements_for_stop_lines.hpp | 12 ------------ ...issing_regulatory_elements_for_traffic_lights.hpp | 12 ------------ ...regulatory_element_details_for_traffic_lights.hpp | 12 ------------ 6 files changed, 2 insertions(+), 62 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/src/main.cpp b/map/autoware_lanelet2_map_validator/src/main.cpp index 07c4b3cc..ad49d005 100644 --- a/map/autoware_lanelet2_map_validator/src/main.cpp +++ b/map/autoware_lanelet2_map_validator/src/main.cpp @@ -143,8 +143,8 @@ int main(int argc, char * argv[]) // Print available validators if (config.command_line_config.print) { - auto checks = lanelet::validation::availabeChecks( - config.command_line_config.validationConfig.checksFilter); // cspell:disable-line + auto checks = lanelet::validation::availabeChecks( // cspell:disable-line + config.command_line_config.validationConfig.checksFilter); if (checks.empty()) { std::cout << "No checks found matching '" << config.command_line_config.validationConfig.checksFilter << "'\n"; diff --git a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp index 67c99fb6..38f83c15 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp +++ b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp @@ -12,15 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -<<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp #ifndef VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ -MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ #define VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ -MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ -======= -#ifndef VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ -#define VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ ->>>>>>> 0fe0b37 (Changed the entire structure.):map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp #include #include @@ -43,9 +36,4 @@ class MissingRegulatoryElementsForCrosswalksValidator : public lanelet::validati } // namespace validation } // namespace lanelet -<<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ - // MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ -======= #endif // VALIDATORS__CROSSWALK__MISSING_REGULATORY_ELEMENTS_FOR_CROSSWALKS_HPP_ ->>>>>>> 0fe0b37 (Changed the entire structure.):map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp diff --git a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp index a2afa429..a352cff6 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp +++ b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp @@ -12,15 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -<<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp #ifndef VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ -REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ #define VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ -REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ -======= -#ifndef VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ -#define VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ ->>>>>>> 0fe0b37 (Changed the entire structure.):map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp #include #include @@ -43,9 +36,4 @@ class RegulatoryElementsDetailsForCrosswalksValidator : public lanelet::validati } // namespace validation } // namespace lanelet -<<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ - // REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ -======= #endif // VALIDATORS__CROSSWALK__REGULATORY_ELEMENT_DETAILS_FOR_CROSSWALKS_HPP_ ->>>>>>> 0fe0b37 (Changed the entire structure.):map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp diff --git a/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp b/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp index 39d88fe7..2e97fa55 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp +++ b/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp @@ -12,15 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -<<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp #ifndef VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ -MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ #define VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ -MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ -======= -#ifndef VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ -#define VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ ->>>>>>> 0fe0b37 (Changed the entire structure.):map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp #include #include @@ -43,9 +36,4 @@ class MissingRegulatoryElementsForStopLinesValidator : public lanelet::validatio } // namespace validation } // namespace lanelet -<<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ - // MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ -======= #endif // VALIDATORS__STOP_LINE__MISSING_REGULATORY_ELEMENTS_FOR_STOP_LINES_HPP_ ->>>>>>> 0fe0b37 (Changed the entire structure.):map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp diff --git a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp index 4f7c9dab..4bb1c4d6 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp +++ b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp @@ -12,15 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -<<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp #ifndef VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ -MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ #define VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ -MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ -======= -#ifndef VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ -#define VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ ->>>>>>> 0fe0b37 (Changed the entire structure.):map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp #include #include @@ -46,9 +39,4 @@ class MissingRegulatoryElementsForTrafficLightsValidator : public lanelet::valid } // namespace validation } // namespace lanelet -<<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ - // MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ -======= #endif // VALIDATORS__TRAFFIC_LIGHT__MISSING_REGULATORY_ELEMENTS_FOR_TRAFFIC_LIGHTS_HPP_ ->>>>>>> 0fe0b37 (Changed the entire structure.):map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp diff --git a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp index ec5fd9ae..d5e64024 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp +++ b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp @@ -12,15 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -<<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp #ifndef VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ -REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ #define VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ -REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ -======= -#ifndef VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ -#define VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ ->>>>>>> 0fe0b37 (Changed the entire structure.):map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp #include #include @@ -50,9 +43,4 @@ class RegulatoryElementsDetailsForTrafficLightsValidator : public lanelet::valid } // namespace validation } // namespace lanelet -<<<<<<< HEAD:map/autoware_lanelet2_map_validator/include/autoware_lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp -#endif // AUTOWARE_LANELET2_MAP_VALIDATOR__VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ - // REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ -======= #endif // VALIDATORS__TRAFFIC_LIGHT__REGULATORY_ELEMENT_DETAILS_FOR_TRAFFIC_LIGHTS_HPP_ ->>>>>>> 0fe0b37 (Changed the entire structure.):map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp From c14477e1fb219193681317f53c8ff78ef1e43ba7 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Tue, 1 Oct 2024 18:34:55 +0900 Subject: [PATCH 25/45] Write more details about the relationship to lanelet2_validation. Rewrite misleading examples. Signed-off-by: TaikiYamada4 --- map/autoware_lanelet2_map_validator/README.md | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/README.md b/map/autoware_lanelet2_map_validator/README.md index ae24d03b..1342bb41 100644 --- a/map/autoware_lanelet2_map_validator/README.md +++ b/map/autoware_lanelet2_map_validator/README.md @@ -1,7 +1,8 @@ # autoware_lanelet2_map_validator `autoware_lanelet2_map_validator` is a tool to validate Lanelet2 maps to ensure that Autoware can work properly with it. -This validation tool is an extension of [lanelet2_validation](https://github.com/fzi-forschungszentrum-informatik/Lanelet2/tree/master/lanelet2_validation) so that Autoware specific rules can be applied. + +This validation tool is an extension of [lanelet2_validation](https://github.com/fzi-forschungszentrum-informatik/Lanelet2/tree/master/lanelet2_validation) so that Autoware specific rules can be applied. As you can see from the codes in the `src/validators` directory, the group of validators belong to this tool inherits the [lanelet::validation::MapValidator class](https://github.com/fzi-forschungszentrum-informatik/Lanelet2/blob/master/lanelet2_validation/include/lanelet2_validation/BasicValidator.h#L17) from the original `lanelet2_validation`. Therefore, we believe that reading the source code of the `lanelet2_validation` will help you understand this tool better. **Note that this validator is still on construction that there are only a few rules and a template to define those rules.** @@ -44,15 +45,15 @@ You can run `autoware_lanelet2_map_validator` with a yaml file input that follow ```yaml requirements: - - id: vm-01-01 + - id: example-01-01 validators: - name: mapping.crosswalk.missing_regulatory_elements - name: mapping.crosswalk.regulatory_element_details - - id: vm-01-02 + - id: example-01-02 validators: - name: mapping.traffic_light.missing_regulatory_elements - name: mapping.traffic_light.regulatory_element_details - - id: vm-01-03 + - id: example-01-03 validators: - name: mapping.stop_line.missing_regulatory_elements ``` @@ -75,7 +76,7 @@ When the `input_requirements` is thrown to `autoware_lanelet2_map_validator`, it ```yaml requirements: - - id: vm-01-01 + - id: example-01-01 passed: false validators: - name: mapping.crosswalk.missing_regulatory_elements @@ -99,7 +100,7 @@ requirements: message: No regulatory element refers to this crosswalk. - name: mapping.crosswalk.regulatory_element_details passed: true - - id: vm-01-02 + - id: exanple-01-02 passed: false validators: - name: mapping.traffic_light.missing_regulatory_elements @@ -123,7 +124,7 @@ requirements: primitive: regulatory element id: 9874 message: Regulatory element of traffic light must have a stop line(ref_line). - - id: vm-01-03 + - id: example-01-03 passed: true validators: - name: mapping.stop_line.missing_regulatory_elements @@ -171,6 +172,7 @@ The directory structure should be the same to that of the `src/lib/validators` d ## Relationship between requirements and validators +This is a table describing the correspondence between the validators that each requirement consists of. The Validators column will be blank if it hasn't be implemented. | ID | Requirements | Validators | From 315dbf04fa1b0bb52f802b7a691e5aed4220717f Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Thu, 3 Oct 2024 12:21:45 +0900 Subject: [PATCH 26/45] Added figure of the architecture Signed-off-by: TaikiYamada4 --- map/autoware_lanelet2_map_validator/README.md | 49 +- ...let2_map_validator_architecture.drawio.svg | 800 ++++++++++++++++++ 2 files changed, 835 insertions(+), 14 deletions(-) create mode 100644 map/autoware_lanelet2_map_validator/media/autoware_lanelet2_map_validator_architecture.drawio.svg diff --git a/map/autoware_lanelet2_map_validator/README.md b/map/autoware_lanelet2_map_validator/README.md index 1342bb41..e6e62ebb 100644 --- a/map/autoware_lanelet2_map_validator/README.md +++ b/map/autoware_lanelet2_map_validator/README.md @@ -8,6 +8,17 @@ This validation tool is an extension of [lanelet2_validation](https://github.com The official Autoware requirements for lanelet2 maps are described in [Vector Map creation requirement specifications (in Autoware Documentation)](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/map/map-requirements/vector-map-requirements-overview/). +## Design concept + +The `autoware_lanelet2_map_validator` is designed to validate `.osm` map files by using and extending the [lanelet2_validation](https://github.com/fzi-forschungszentrum-informatik/Lanelet2/tree/master/lanelet2_validation) package for Autoware. + +`autoware_lanelet2_map_validator` takes the lanelet2 map (.osm file) and requirement set (yaml file, optional) as the input, and output validation results to the console. + +If a requirement set is given, `autoware_lanelet2_map_validator` also outputs validation results reflecting the input requirement set. +See ["Run with a requirement set"](#run-with-a-requirement-set) for further information, ["Input file"](#input-file) to understand the input format, and ["Output file"](#output-file) to understand the output format. + +![autoware_lanelet2_map_validator_architecture](./media/autoware_lanelet2_map_validator_architecture.drawio.svg) + ## How to use Basically, you can use the following command to execute `autoware_lanelet2_map_validator`. However, note that `autoware_lanelet2_map_validator` is a ROS/rclcpp free tool, so you can just run the built executable whatever way. @@ -41,12 +52,24 @@ ros2 run autoware_lanelet2_map_validator autoware_lanelet2_map_validator --print ### Run with a requirement set -You can run `autoware_lanelet2_map_validator` with a yaml file input that follows the structure like this +`autoware_lanelet2_map_validator` can manage to run a group of validators by a list of validator names. +`autoware_lanelet2_map_validator` will scan through the input yaml file given by the `--input_requirements, -i` option, and output the validation results to the directory given by the `--output_directory, -o` option. +The output filename will be `lanelet2_validation_results.yaml`. + +```bash +ros2 run autoware_lanelet2_map_validator autoware_lanelet2_map_validator --input_requirements autoware_requirements_set.yaml --output_directory ./ +``` + +#### Input file + +The yaml file input should follow the structure like this ```yaml -requirements: - - id: example-01-01 - validators: +# input example +version: 0.1.0 # Not required. You can add any field if the "requirements" field is set correctly. +requirements: # Required. + - id: example-01-01 # Users have to set ids to a group of validators. The id name is arbitrary. + validators: # List up validator names that consists of the requirement. - name: mapping.crosswalk.missing_regulatory_elements - name: mapping.crosswalk.regulatory_element_details - id: example-01-02 @@ -66,22 +89,20 @@ requirements: - The name list of available validators can be obtained from the `--print` option. - The user can write any other field (like `version`) besides `requirements`. -Then, the `autoware_lanelet2_map_validator` will scan through the input yaml file given by the `--input_requirements, -i` option, and output the validation results to the directory given by the `--output_directory, -o` option. - -```bash -ros2 run autoware_lanelet2_map_validator autoware_lanelet2_map_validator --input_requirements autoware_requirements_set.yaml --output_directory ./ -``` +#### Output file When the `input_requirements` is thrown to `autoware_lanelet2_map_validator`, it will output a `lanelet2_validation_results.yaml` file which looks like the following. ```yaml +# output example +version: 0.1.0 # non-required fields in the input file will remain still requirements: - id: example-01-01 - passed: false + passed: false # True if all validators within the id have passed. validators: - name: mapping.crosswalk.missing_regulatory_elements - passed: false - issues: + passed: false # True if this single validator have passed + issues: # If there are issues, they will be list up here - severity: Error primitive: lanelet id: 163 @@ -99,8 +120,8 @@ requirements: id: 166 message: No regulatory element refers to this crosswalk. - name: mapping.crosswalk.regulatory_element_details - passed: true - - id: exanple-01-02 + passed: true # If the validation have passed, no issues appear + - id: example-01-02 passed: false validators: - name: mapping.traffic_light.missing_regulatory_elements diff --git a/map/autoware_lanelet2_map_validator/media/autoware_lanelet2_map_validator_architecture.drawio.svg b/map/autoware_lanelet2_map_validator/media/autoware_lanelet2_map_validator_architecture.drawio.svg new file mode 100644 index 00000000..d8ee4716 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/media/autoware_lanelet2_map_validator_architecture.drawio.svg @@ -0,0 +1,800 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ autoware_lanelet2_map_validator +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + + +
+
+
+ lanelet2_map.osm +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + +
+
+
+ requirement_set.yaml +
+
+
+
+ +
+
+
+
+ + + + + + + + + + +
+
+
+ lanelet2_validation_results.yaml +
+
+
+
+ +
+
+
+
+ + + + + + + + + + +
+
+
+ traffic light +
+
+
+
+ +
+
+
+ + + + + + + + +
+
+
+ - mapping.traffic_light.missing_regulatory_elements +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ - mapping.traffic_light.regulatory_element_details +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ - + and more... +
+
+
+
+ +
+
+
+
+
+ + + + + + + + + + +
+
+
+ crosswalk +
+
+
+
+ +
+
+
+ + + + + + + + +
+
+
+ - mapping.crosswalk.missing_regulatory_elements +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ - mapping.crosswalk.regulatory_element_details +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ - + and more... +
+
+
+
+ +
+
+
+
+
+ + + + + + + + + + +
+
+
+ stop line +
+
+
+
+ +
+
+
+ + + + + + + + +
+
+
+ - mapping.stop_line.missing_regulatory_elements +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ + - + + and more... +
+
+
+
+
+
+
+ +
+
+
+
+
+ + + + + + + + +
+
+
+ autoware_lanelet2_map_validator contains a bunch of validators, and calls the ones written in the requirement_set.yaml +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Input +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Output +
+
+
+
+ +
+
+
+
+ + + + + + + + + +
+
+
+ + + and more other categories... +
+
+
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ console output +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ + Only if a requirement set input is given + +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ + + Optional, but recommended +
+
+
+
+
+
+
+ +
+
+
+
+
+
+
+
From 2f7d839e0abb412fb909c9323a61fa1f7861a7b7 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Thu, 3 Oct 2024 18:01:57 +0900 Subject: [PATCH 27/45] Change the input/output to JSON Signed-off-by: TaikiYamada4 --- .../CMakeLists.txt | 6 +- map/autoware_lanelet2_map_validator/README.md | 229 +++++++++++------- .../autoware_requirement_set.json | 26 ++ .../autoware_requirement_set.yaml | 9 - .../package.xml | 2 +- .../src/main.cpp | 65 ++--- .../test/example_requirement_set.json | 35 +++ .../test/test_requirement_set.yaml | 13 - 8 files changed, 243 insertions(+), 142 deletions(-) create mode 100644 map/autoware_lanelet2_map_validator/autoware_requirement_set.json delete mode 100644 map/autoware_lanelet2_map_validator/autoware_requirement_set.yaml create mode 100644 map/autoware_lanelet2_map_validator/test/example_requirement_set.json delete mode 100644 map/autoware_lanelet2_map_validator/test/test_requirement_set.yaml diff --git a/map/autoware_lanelet2_map_validator/CMakeLists.txt b/map/autoware_lanelet2_map_validator/CMakeLists.txt index c0502dd0..f80d4b7d 100644 --- a/map/autoware_lanelet2_map_validator/CMakeLists.txt +++ b/map/autoware_lanelet2_map_validator/CMakeLists.txt @@ -5,7 +5,7 @@ find_package(autoware_cmake REQUIRED) autoware_package() ament_auto_find_build_dependencies() -find_package(yaml-cpp REQUIRED) +find_package(nlohmann_json REQUIRED) include_directories( src @@ -20,7 +20,7 @@ ament_auto_add_executable(autoware_lanelet2_map_validator src/main.cpp) add_dependencies(autoware_lanelet2_map_validator autoware_lanelet2_map_validator_lib) target_link_libraries(autoware_lanelet2_map_validator autoware_lanelet2_map_validator_lib - yaml-cpp + nlohmann_json ) if(BUILD_TESTING) @@ -32,7 +32,7 @@ if(BUILD_TESTING) target_link_libraries( ${VALIDATION_NAME}_test autoware_lanelet2_map_validator_lib - yaml-cpp + nlohmann_json ) endfunction() diff --git a/map/autoware_lanelet2_map_validator/README.md b/map/autoware_lanelet2_map_validator/README.md index e6e62ebb..3a85e9cf 100644 --- a/map/autoware_lanelet2_map_validator/README.md +++ b/map/autoware_lanelet2_map_validator/README.md @@ -12,7 +12,7 @@ The official Autoware requirements for lanelet2 maps are described in [Vector Ma The `autoware_lanelet2_map_validator` is designed to validate `.osm` map files by using and extending the [lanelet2_validation](https://github.com/fzi-forschungszentrum-informatik/Lanelet2/tree/master/lanelet2_validation) package for Autoware. -`autoware_lanelet2_map_validator` takes the lanelet2 map (.osm file) and requirement set (yaml file, optional) as the input, and output validation results to the console. +`autoware_lanelet2_map_validator` takes the lanelet2 map (.osm file) and requirement set (JSON file, optional) as the input, and output validation results to the console. If a requirement set is given, `autoware_lanelet2_map_validator` also outputs validation results reflecting the input requirement set. See ["Run with a requirement set"](#run-with-a-requirement-set) for further information, ["Input file"](#input-file) to understand the input format, and ["Output file"](#output-file) to understand the output format. @@ -53,37 +53,58 @@ ros2 run autoware_lanelet2_map_validator autoware_lanelet2_map_validator --print ### Run with a requirement set `autoware_lanelet2_map_validator` can manage to run a group of validators by a list of validator names. -`autoware_lanelet2_map_validator` will scan through the input yaml file given by the `--input_requirements, -i` option, and output the validation results to the directory given by the `--output_directory, -o` option. -The output filename will be `lanelet2_validation_results.yaml`. +`autoware_lanelet2_map_validator` will scan through the input JSON file given by the `--input_requirements, -i` option, and output the validation results to the directory given by the `--output_directory, -o` option. +The output filename will be `lanelet2_validation_results.json`. ```bash -ros2 run autoware_lanelet2_map_validator autoware_lanelet2_map_validator --input_requirements autoware_requirements_set.yaml --output_directory ./ +ros2 run autoware_lanelet2_map_validator autoware_lanelet2_map_validator --input_requirements autoware_requirements_set.json --output_directory ./ ``` #### Input file -The yaml file input should follow the structure like this - -```yaml -# input example -version: 0.1.0 # Not required. You can add any field if the "requirements" field is set correctly. -requirements: # Required. - - id: example-01-01 # Users have to set ids to a group of validators. The id name is arbitrary. - validators: # List up validator names that consists of the requirement. - - name: mapping.crosswalk.missing_regulatory_elements - - name: mapping.crosswalk.regulatory_element_details - - id: example-01-02 - validators: - - name: mapping.traffic_light.missing_regulatory_elements - - name: mapping.traffic_light.regulatory_element_details - - id: example-01-03 - validators: - - name: mapping.stop_line.missing_regulatory_elements +The JSON file input should follow the structure like this example. + +```json +{ + "version": "0.1.0", + "requirements": [ + { + "id": "example-01-01", + "validators": [ + { + "name": "mapping.crosswalk.missing_regulatory_elements" + }, + { + "name": "mapping.crosswalk.regulatory_element_details" + } + ] + }, + { + "id": "example-01-02", + "validators": [ + { + "name": "mapping.traffic_light.missing_regulatory_elements" + }, + { + "name": "mapping.traffic_light.regulatory_element_details" + } + ] + }, + { + "id": "example-01-03", + "validators": [ + { + "name": "mapping.stop_line.missing_regulatory_elements" + } + ] + } + ] +} ``` - MUST have a single `requirements` field. - The `requirements` field MUST be a list of requirements. A requirement MUST have - - `id` : The id of the requirement. + - `id` : The id of the requirement. Its name is arbitrary. - `validators` : A list of validators that structures the requirement. - A validator MUST be given with its name on the `name` field. - The name list of available validators can be obtained from the `--print` option. @@ -91,68 +112,108 @@ requirements: # Required. #### Output file -When the `input_requirements` is thrown to `autoware_lanelet2_map_validator`, it will output a `lanelet2_validation_results.yaml` file which looks like the following. - -```yaml -# output example -version: 0.1.0 # non-required fields in the input file will remain still -requirements: - - id: example-01-01 - passed: false # True if all validators within the id have passed. - validators: - - name: mapping.crosswalk.missing_regulatory_elements - passed: false # True if this single validator have passed - issues: # If there are issues, they will be list up here - - severity: Error - primitive: lanelet - id: 163 - message: No regulatory element refers to this crosswalk. - - severity: Error - primitive: lanelet - id: 164 - message: No regulatory element refers to this crosswalk. - - severity: Error - primitive: lanelet - id: 165 - message: No regulatory element refers to this crosswalk. - - severity: Error - primitive: lanelet - id: 166 - message: No regulatory element refers to this crosswalk. - - name: mapping.crosswalk.regulatory_element_details - passed: true # If the validation have passed, no issues appear - - id: example-01-02 - passed: false - validators: - - name: mapping.traffic_light.missing_regulatory_elements - passed: true - - name: mapping.traffic_light.regulatory_element_details - passed: false - issues: - - severity: Error - primitive: regulatory element - id: 9896 - message: Regulatory element of traffic light must have a stop line(ref_line). - - severity: Error - primitive: regulatory element - id: 9918 - message: Regulatory element of traffic light must have a stop line(ref_line). - - severity: Error - primitive: regulatory element - id: 9838 - message: Regulatory element of traffic light must have a stop line(ref_line). - - severity: Error - primitive: regulatory element - id: 9874 - message: Regulatory element of traffic light must have a stop line(ref_line). - - id: example-01-03 - passed: true - validators: - - name: mapping.stop_line.missing_regulatory_elements - passed: true +When the `input_requirements` is thrown to `autoware_lanelet2_map_validator`, it will output a `lanelet2_validation_results.json` file which looks like the following example. + +```json +{ + "requirements": [ + { + "id": "example-01-01", + "passed": false, + "validators": [ + { + "issues": [ + { + "id": 163, + "message": "No regulatory element refers to this crosswalk.", + "primitive": "lanelet", + "severity": "Error" + }, + { + "id": 164, + "message": "No regulatory element refers to this crosswalk.", + "primitive": "lanelet", + "severity": "Error" + }, + { + "id": 165, + "message": "No regulatory element refers to this crosswalk.", + "primitive": "lanelet", + "severity": "Error" + }, + { + "id": 166, + "message": "No regulatory element refers to this crosswalk.", + "primitive": "lanelet", + "severity": "Error" + } + ], + "name": "mapping.crosswalk.missing_regulatory_elements", + "passed": false + }, + { + "name": "mapping.crosswalk.regulatory_element_details", + "passed": true + } + ] + }, + { + "id": "example-01-02", + "passed": false, + "validators": [ + { + "name": "mapping.traffic_light.missing_regulatory_elements", + "passed": true + }, + { + "issues": [ + { + "id": 9896, + "message": "Regulatory element of traffic light must have a stop line(ref_line).", + "primitive": "regulatory element", + "severity": "Error" + }, + { + "id": 9918, + "message": "Regulatory element of traffic light must have a stop line(ref_line).", + "primitive": "regulatory element", + "severity": "Error" + }, + { + "id": 9838, + "message": "Regulatory element of traffic light must have a stop line(ref_line).", + "primitive": "regulatory element", + "severity": "Error" + }, + { + "id": 9874, + "message": "Regulatory element of traffic light must have a stop line(ref_line).", + "primitive": "regulatory element", + "severity": "Error" + } + ], + "name": "mapping.traffic_light.regulatory_element_details", + "passed": false + } + ] + }, + { + "id": "example-01-03", + "passed": true, + "validators": [ + { + "name": "mapping.stop_line.missing_regulatory_elements", + "passed": true + } + ] + } + ], + "version": "0.1.0" +} ``` -- `lanelet2_validation_results.yaml` inherits the yaml file of `input_requirements` and add results to it. +- `lanelet2_validation_results.json` inherits the JSON file of `input_requirements` and add results to it. + - So non-required fields (line `version`) remains in the output. - `autoware_lanelet2_map_validator` adds a boolean `passed` field to each requirement. If all validators of the requirement have been passed, the `passed` field of the requirement will be `true` (`false` if not). - The `passed` field is also given to each validator. If the validator found any issues the `passed` field will turn to be `false` (`true` if not), and adds an `issues` field which is a list of issues found. Each issues contains information of `severity`, `primitive`, `id`, and `message`. @@ -163,8 +224,8 @@ requirements: | `-h, --help` | Explains about this tool and show a list of options | | `--print` | Print all available checker without running them | | `-m, --map_file` | Path to the map to be validated | -| `-i, --input_requirements` | Path to the yaml file where the list of requirements and validations is written | -| `-o, --output_directory` | Directory to save the list of validation results in a yaml format | +| `-i, --input_requirements` | Path to the JSON file where the list of requirements and validations is written | +| `-o, --output_directory` | Directory to save the list of validation results in a JSON format | | `-v, --validator` | Comma separated list of regexes to filter the applicable validators. Will run all validators by default. Example: `mapping.*` to run all checks for the mapping | | `-p, --projector` | Projector used for loading lanelet map. Available projectors are: mgrs, utm, transverse_mercator. (default: mgrs) | | `-l, --location` | Location of the map (for instantiating the traffic rules), e.g. de for Germany | diff --git a/map/autoware_lanelet2_map_validator/autoware_requirement_set.json b/map/autoware_lanelet2_map_validator/autoware_requirement_set.json new file mode 100644 index 00000000..6277a712 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/autoware_requirement_set.json @@ -0,0 +1,26 @@ +{ + "requirements": [ + { + "id": "vm-04-01", + "validators": [ + { + "name": "mapping.crosswalk.missing_regulatory_elements" + }, + { + "name": "mapping.crosswalk.regulatory_element_details" + } + ] + }, + { + "id": "vm-05-01", + "validators": [ + { + "name": "mapping.traffic_light.missing_regulatory_elements" + }, + { + "name": "mapping.traffic_light.regulatory_element_details" + } + ] + } + ] +} diff --git a/map/autoware_lanelet2_map_validator/autoware_requirement_set.yaml b/map/autoware_lanelet2_map_validator/autoware_requirement_set.yaml deleted file mode 100644 index 9437fb00..00000000 --- a/map/autoware_lanelet2_map_validator/autoware_requirement_set.yaml +++ /dev/null @@ -1,9 +0,0 @@ -requirements: - - id: vm-04-01 - validators: - - name: mapping.crosswalk.missing_regulatory_elements - - name: mapping.crosswalk.regulatory_element_details - - id: vm-05-01 - validators: - - name: mapping.traffic_light.missing_regulatory_elements - - name: mapping.traffic_light.regulatory_element_details diff --git a/map/autoware_lanelet2_map_validator/package.xml b/map/autoware_lanelet2_map_validator/package.xml index 270c454b..23fde3b4 100644 --- a/map/autoware_lanelet2_map_validator/package.xml +++ b/map/autoware_lanelet2_map_validator/package.xml @@ -18,7 +18,7 @@ lanelet2_routing lanelet2_traffic_rules lanelet2_validation - yaml-cpp + nlohmann_json ament_cmake_ros diff --git a/map/autoware_lanelet2_map_validator/src/main.cpp b/map/autoware_lanelet2_map_validator/src/main.cpp index ad49d005..e92f13eb 100644 --- a/map/autoware_lanelet2_map_validator/src/main.cpp +++ b/map/autoware_lanelet2_map_validator/src/main.cpp @@ -17,11 +17,14 @@ #include "lib/utils.hpp" #include "lib/validation.hpp" -#include +#include #include #include +// Use nlohmann::json for JSON hndling +using json = nlohmann::json; + // ANSI color codes for console output #define BOLD_ONLY "\033[1m" #define BOLD_GREEN "\033[1;32m" @@ -32,21 +35,21 @@ #define FONT_RESET "\033[0m" int process_requirements( - YAML::Node yaml_config, const lanelet::autoware::validation::MetaConfig & validator_config) + json json_config, const lanelet::autoware::validation::MetaConfig & validator_config) { uint64_t warning_count = 0; uint64_t error_count = 0; lanelet::autoware::validation::MetaConfig temp_validator_config = validator_config; - for (YAML::Node requirement : yaml_config["requirements"]) { - std::string id = requirement["id"].as(); + for (auto & requirement : json_config["requirements"]) { + std::string id = requirement["id"]; bool requirement_passed = true; std::vector issues; std::map temp_validation_results; - for (YAML::Node validator : requirement["validators"]) { - std::string validator_name = validator["name"].as(); + for (auto & validator : requirement["validators"]) { + std::string validator_name = validator["name"]; temp_validator_config.command_line_config.validationConfig.checksFilter = validator_name; std::vector temp_issues = @@ -63,16 +66,17 @@ int process_requirements( error_count += temp_issues[0].errors().size(); temp_validation_results[validator_name] = false; validator["passed"] = false; - YAML::Node issues_node = YAML::Node(YAML::NodeType::Sequence); - for (lanelet::validation::Issue issue : temp_issues[0].issues) { - YAML::Node issue_node; - issue_node["severity"] = lanelet::validation::toString(issue.severity); - issue_node["primitive"] = lanelet::validation::toString(issue.primitive); - issue_node["id"] = issue.id; - issue_node["message"] = issue.message; - issues_node.push_back(issue_node); + + json issues_json; + for (const auto & issue : temp_issues[0].issues) { + json issue_json; + issue_json["severity"] = lanelet::validation::toString(issue.severity); + issue_json["primitive"] = lanelet::validation::toString(issue.primitive); + issue_json["id"] = issue.id; + issue_json["message"] = issue.message; + issues_json.push_back(issue_json); } - validator["issues"] = issues_node; + validator["issues"] = issues_json; } lanelet::autoware::validation::appendIssues(issues, std::move(temp_issues)); @@ -88,11 +92,6 @@ int process_requirements( std::cout << BOLD_RED << "Failed" << FONT_RESET << std::endl; } - // In order to make "passed" field above then the "validators" field in the output file. - YAML::Node temp_validators = requirement["validators"]; - requirement.remove("validators"); - requirement["validators"] = temp_validators; - for (const auto & result : temp_validation_results) { if (result.second) { std::cout << " - " << result.first << ": " << NORMAL_GREEN << "Passed" << FONT_RESET @@ -121,9 +120,9 @@ int process_requirements( } if (!validator_config.output_file_path.empty()) { - std::string file_name = validator_config.output_file_path + "/lanelet2_validation_results.yaml"; + std::string file_name = validator_config.output_file_path + "/lanelet2_validation_results.json"; std::ofstream output_file(file_name); - output_file << yaml_config; + output_file << std::setw(4) << json_config; std::cout << "Results are output to " << file_name << std::endl; } @@ -132,22 +131,22 @@ int process_requirements( int main(int argc, char * argv[]) { - lanelet::autoware::validation::MetaConfig config = + lanelet::autoware::validation::MetaConfig meta_config = lanelet::autoware::validation::parseCommandLine( argc, const_cast(argv)); // NOLINT // Print help (Already done in parseCommandLine) - if (config.command_line_config.help) { + if (meta_config.command_line_config.help) { return 0; } // Print available validators - if (config.command_line_config.print) { + if (meta_config.command_line_config.print) { auto checks = lanelet::validation::availabeChecks( // cspell:disable-line - config.command_line_config.validationConfig.checksFilter); + meta_config.command_line_config.validationConfig.checksFilter); if (checks.empty()) { std::cout << "No checks found matching '" - << config.command_line_config.validationConfig.checksFilter << "'\n"; + << meta_config.command_line_config.validationConfig.checksFilter << "'\n"; } else { std::cout << "The following checks are available:\n"; for (auto & check : checks) { @@ -158,17 +157,19 @@ int main(int argc, char * argv[]) } // Check whether the map_file is specified - if (config.command_line_config.mapFile.empty()) { + if (meta_config.command_line_config.mapFile.empty()) { std::cout << "No map file specified" << std::endl; return 1; } // Validation start - if (!config.requirements_file.empty()) { - YAML::Node yaml_config = YAML::LoadFile(config.requirements_file); - return process_requirements(yaml_config, config); + if (!meta_config.requirements_file.empty()) { + std::ifstream input_file(meta_config.requirements_file); + json json_config; + input_file >> json_config; + return process_requirements(json_config, meta_config); } else { - auto issues = lanelet::autoware::validation::validateMap(config); + auto issues = lanelet::autoware::validation::validateMap(meta_config); lanelet::validation::printAllIssues(issues); return static_cast(!issues.empty()); } diff --git a/map/autoware_lanelet2_map_validator/test/example_requirement_set.json b/map/autoware_lanelet2_map_validator/test/example_requirement_set.json new file mode 100644 index 00000000..445be17a --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/example_requirement_set.json @@ -0,0 +1,35 @@ +{ + "version": "0.1.0", + "requirements": [ + { + "id": "example-01-01", + "validators": [ + { + "name": "mapping.crosswalk.missing_regulatory_elements" + }, + { + "name": "mapping.crosswalk.regulatory_element_details" + } + ] + }, + { + "id": "example-01-02", + "validators": [ + { + "name": "mapping.traffic_light.missing_regulatory_elements" + }, + { + "name": "mapping.traffic_light.regulatory_element_details" + } + ] + }, + { + "id": "example-01-03", + "validators": [ + { + "name": "mapping.stop_line.missing_regulatory_elements" + } + ] + } + ] +} diff --git a/map/autoware_lanelet2_map_validator/test/test_requirement_set.yaml b/map/autoware_lanelet2_map_validator/test/test_requirement_set.yaml deleted file mode 100644 index 19e5487f..00000000 --- a/map/autoware_lanelet2_map_validator/test/test_requirement_set.yaml +++ /dev/null @@ -1,13 +0,0 @@ -version: 0.0.1 -requirements: - - id: test-01 - validators: - - name: mapping.crosswalk.missing_regulatory_elements - - name: mapping.crosswalk.regulatory_element_details - - id: test-02 - validators: - - name: mapping.traffic_light.missing_regulatory_elements - - name: mapping.traffic_light.regulatory_element_details - - id: test-03 - validators: - - name: mapping.stop_line.missing_regulatory_elements From f5ec7660af14b36e41fa7a0b3febbcc285313db3 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Thu, 10 Oct 2024 11:10:18 +0900 Subject: [PATCH 28/45] Revised architecture image of autoware_lanelet2_map_validator Signed-off-by: TaikiYamada4 --- ...let2_map_validator_architecture.drawio.svg | 33 ++++++++----------- 1 file changed, 14 insertions(+), 19 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/media/autoware_lanelet2_map_validator_architecture.drawio.svg b/map/autoware_lanelet2_map_validator/media/autoware_lanelet2_map_validator_architecture.drawio.svg index d8ee4716..1bdada5c 100644 --- a/map/autoware_lanelet2_map_validator/media/autoware_lanelet2_map_validator_architecture.drawio.svg +++ b/map/autoware_lanelet2_map_validator/media/autoware_lanelet2_map_validator_architecture.drawio.svg @@ -9,22 +9,17 @@ width="701px" height="481px" viewBox="-0.5 -0.5 701 481" - content="<mxfile host="app.diagrams.net" agent="Mozilla/5.0 (X11; Ubuntu; Linux x86_64; rv:130.0) Gecko/20100101 Firefox/130.0" version="24.7.16" pages="2" scale="1" border="0"> <diagram name="ページ1" id="txHnBQ8Bwk_QwKYoOu-f"> <mxGraphModel dx="2169" dy="747" grid="1" gridSize="10" guides="1" tooltips="1" connect="1" arrows="1" fold="1" page="1" pageScale="1" pageWidth="827" pageHeight="1169" math="0" shadow="0"> <root> <mxCell id="0" /> <mxCell id="1" parent="0" /> <mxCell id="5tm8MCw5WYpOVBz9AR-8-2" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=1;exitY=0.25;exitDx=0;exitDy=0;entryX=0;entryY=0.5;entryDx=0;entryDy=0;" edge="1" parent="1" source="pZbjCYV6troIvum8nigY-1" target="8BQUtLSBopQVORKjeofY-4"> <mxGeometry relative="1" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-1" value="autoware_lanelet2_map_validator" style="rounded=1;whiteSpace=wrap;html=1;strokeColor=#FF0000;strokeWidth=5;" vertex="1" parent="1"> <mxGeometry x="-630" y="565" width="260" height="100" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-21" value="" style="shape=callout;whiteSpace=wrap;html=1;perimeter=calloutPerimeter;rotation=-180;position2=0.55;fillColor=#FFEEF0;strokeColor=#FF0000;size=50;position=0.5;" vertex="1" parent="1"> <mxGeometry x="-800" y="670" width="660" height="310" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-5" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=0;exitY=0;exitDx=150;exitDy=35;exitPerimeter=0;entryX=0;entryY=0.25;entryDx=0;entryDy=0;" edge="1" parent="1" source="pZbjCYV6troIvum8nigY-2" target="pZbjCYV6troIvum8nigY-1"> <mxGeometry relative="1" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-2" value="lanelet2_map.osm" style="shape=note;whiteSpace=wrap;html=1;backgroundOutline=1;darkOpacity=0.05;size=15;fillColor=#fff2cc;strokeColor=#8C7738;" vertex="1" parent="1"> <mxGeometry x="-820" y="540" width="150" height="55" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-6" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=0;exitY=0;exitDx=150;exitDy=35;exitPerimeter=0;entryX=0;entryY=0.75;entryDx=0;entryDy=0;dashed=1;" edge="1" parent="1" source="pZbjCYV6troIvum8nigY-3" target="pZbjCYV6troIvum8nigY-1"> <mxGeometry relative="1" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-3" value="requirement_set.yaml" style="shape=note;whiteSpace=wrap;html=1;backgroundOutline=1;darkOpacity=0.05;size=15;fillColor=#fff2cc;strokeColor=#8C7738;" vertex="1" parent="1"> <mxGeometry x="-820" y="630" width="150" height="55" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-4" value="lanelet2_validation_results.yaml" style="shape=note;whiteSpace=wrap;html=1;backgroundOutline=1;darkOpacity=0.05;size=15;fillColor=#CCFFFF;strokeColor=#8C7738;" vertex="1" parent="1"> <mxGeometry x="-330" y="632" width="210" height="53" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-8" value="&lt;b&gt;traffic light&lt;/b&gt;" style="swimlane;fontStyle=0;childLayout=stackLayout;horizontal=1;startSize=30;horizontalStack=0;resizeParent=1;resizeParentMax=0;resizeLast=0;collapsible=1;marginBottom=0;whiteSpace=wrap;html=1;" vertex="1" parent="1"> <mxGeometry x="-775" y="840" width="300" height="120" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-9" value="- mapping.traffic_light.missing_regulatory_elements" style="text;align=left;verticalAlign=middle;spacingLeft=4;spacingRight=4;overflow=hidden;points=[[0,0.5],[1,0.5]];portConstraint=eastwest;rotatable=0;whiteSpace=wrap;html=1;fillColor=default;strokeColor=default;" vertex="1" parent="pZbjCYV6troIvum8nigY-8"> <mxGeometry y="30" width="300" height="30" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-10" value="- mapping.traffic_light.regulatory_element_details" style="text;align=left;verticalAlign=middle;spacingLeft=4;spacingRight=4;overflow=hidden;points=[[0,0.5],[1,0.5]];portConstraint=eastwest;rotatable=0;whiteSpace=wrap;html=1;fillColor=default;strokeColor=default;" vertex="1" parent="pZbjCYV6troIvum8nigY-8"> <mxGeometry y="60" width="300" height="30" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-27" value="- &lt;i&gt;and more...&lt;/i&gt;" style="text;align=left;verticalAlign=middle;spacingLeft=4;spacingRight=4;overflow=hidden;points=[[0,0.5],[1,0.5]];portConstraint=eastwest;rotatable=0;whiteSpace=wrap;html=1;fillColor=default;strokeColor=default;" vertex="1" parent="pZbjCYV6troIvum8nigY-8"> <mxGeometry y="90" width="300" height="30" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-17" value="&lt;b&gt;crosswalk&lt;/b&gt;" style="swimlane;fontStyle=0;childLayout=stackLayout;horizontal=1;startSize=30;horizontalStack=0;resizeParent=1;resizeParentMax=0;resizeLast=0;collapsible=1;marginBottom=0;whiteSpace=wrap;html=1;" vertex="1" parent="1"> <mxGeometry x="-465" y="740" width="300" height="120" as="geometry"> <mxRectangle x="-465" y="730" width="100" height="30" as="alternateBounds" /> </mxGeometry> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-18" value="- mapping.crosswalk.missing_regulatory_elements" style="text;align=left;verticalAlign=middle;spacingLeft=4;spacingRight=4;overflow=hidden;points=[[0,0.5],[1,0.5]];portConstraint=eastwest;rotatable=0;whiteSpace=wrap;html=1;fillColor=default;strokeColor=default;" vertex="1" parent="pZbjCYV6troIvum8nigY-17"> <mxGeometry y="30" width="300" height="30" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-19" value="- mapping.crosswalk.regulatory_element_details" style="text;align=left;verticalAlign=middle;spacingLeft=4;spacingRight=4;overflow=hidden;points=[[0,0.5],[1,0.5]];portConstraint=eastwest;rotatable=0;whiteSpace=wrap;html=1;fillColor=default;strokeColor=default;" vertex="1" parent="pZbjCYV6troIvum8nigY-17"> <mxGeometry y="60" width="300" height="30" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-28" value="- &lt;i&gt;and more...&lt;/i&gt;" style="text;align=left;verticalAlign=middle;spacingLeft=4;spacingRight=4;overflow=hidden;points=[[0,0.5],[1,0.5]];portConstraint=eastwest;rotatable=0;whiteSpace=wrap;html=1;fillColor=default;strokeColor=default;" vertex="1" parent="pZbjCYV6troIvum8nigY-17"> <mxGeometry y="90" width="300" height="30" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-13" value="&lt;b&gt;stop line&lt;/b&gt;" style="swimlane;fontStyle=0;childLayout=stackLayout;horizontal=1;startSize=30;horizontalStack=0;resizeParent=1;resizeParentMax=0;resizeLast=0;collapsible=1;marginBottom=0;whiteSpace=wrap;html=1;" vertex="1" parent="1"> <mxGeometry x="-775" y="740" width="300" height="90" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-14" value="&lt;font face=&quot;Helvetica&quot;&gt;- mapping.stop_line.missing_regulatory_elements&lt;/font&gt;" style="text;align=left;verticalAlign=middle;spacingLeft=4;spacingRight=4;overflow=hidden;points=[[0,0.5],[1,0.5]];portConstraint=eastwest;rotatable=0;whiteSpace=wrap;html=1;fillColor=default;strokeColor=default;" vertex="1" parent="pZbjCYV6troIvum8nigY-13"> <mxGeometry y="30" width="300" height="30" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-26" value="&lt;font face=&quot;Helvetica&quot;&gt;- &lt;i&gt;and more...&lt;br&gt;&lt;/i&gt;&lt;/font&gt;" style="text;align=left;verticalAlign=middle;spacingLeft=4;spacingRight=4;overflow=hidden;points=[[0,0.5],[1,0.5]];portConstraint=eastwest;rotatable=0;whiteSpace=wrap;html=1;fillColor=default;strokeColor=default;" vertex="1" parent="pZbjCYV6troIvum8nigY-13"> <mxGeometry y="60" width="300" height="30" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-22" value="autoware_lanelet2_map_validator contains a bunch of validators, and calls the ones written in the requirement_set.yaml" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;fontStyle=2;fillColor=default;opacity=70;" vertex="1" parent="1"> <mxGeometry x="-450" y="910" width="270" height="50" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-23" value="&lt;font style=&quot;font-size: 18px;&quot;&gt;Input&lt;/font&gt;" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;fontStyle=1" vertex="1" parent="1"> <mxGeometry x="-775" y="500" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-24" value="&lt;font style=&quot;font-size: 18px;&quot;&gt;Output&lt;/font&gt;" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;fontStyle=1" vertex="1" parent="1"> <mxGeometry x="-255" y="500" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-29" value="&lt;b&gt;&lt;i&gt;and more other categories...&lt;br&gt;&lt;/i&gt;&lt;/b&gt;" style="swimlane;fontStyle=0;childLayout=stackLayout;horizontal=1;startSize=30;horizontalStack=0;resizeParent=1;resizeParentMax=0;resizeLast=0;collapsible=1;marginBottom=0;whiteSpace=wrap;html=1;" vertex="1" collapsed="1" parent="1"> <mxGeometry x="-412.5" y="870" width="195" height="30" as="geometry"> <mxRectangle x="-465" y="860" width="300" height="60" as="alternateBounds" /> </mxGeometry> </mxCell> <mxCell id="8BQUtLSBopQVORKjeofY-4" value="&lt;font color=&quot;#b3ff66&quot;&gt;console output&lt;/font&gt;" style="rounded=0;whiteSpace=wrap;html=1;strokeColor=#E6E6E6;fillColor=#241F31;" vertex="1" parent="1"> <mxGeometry x="-330" y="540" width="210" height="53" as="geometry" /> </mxCell> <mxCell id="5tm8MCw5WYpOVBz9AR-8-1" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=1;exitY=0.75;exitDx=0;exitDy=0;entryX=0;entryY=0.5;entryDx=0;entryDy=0;entryPerimeter=0;dashed=1;" edge="1" parent="1" source="pZbjCYV6troIvum8nigY-1" target="pZbjCYV6troIvum8nigY-4"> <mxGeometry relative="1" as="geometry" /> </mxCell> <mxCell id="5tm8MCw5WYpOVBz9AR-8-3" value="&lt;font style=&quot;font-size: 10px;&quot;&gt;&lt;i&gt;Only if a requirement set input is given&lt;/i&gt;&lt;/font&gt;" style="text;html=1;align=right;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="1"> <mxGeometry x="-345" y="680" width="220" height="25" as="geometry" /> </mxCell> <mxCell id="5tm8MCw5WYpOVBz9AR-8-4" value="&lt;font style=&quot;font-size: 10px;&quot;&gt;&lt;i&gt;Optional, but recommended&lt;br&gt;&lt;/i&gt;&lt;/font&gt;" style="text;html=1;align=right;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="1"> <mxGeometry x="-820" y="680" width="150" height="25" as="geometry" /> </mxCell> </root> </mxGraphModel> </diagram> <diagram id="Y81l0PrR7Q6dCZwbgd-N" name="ページ2"> <mxGraphModel dx="3140" dy="1288" grid="1" gridSize="10" guides="1" tooltips="1" connect="1" arrows="1" fold="1" page="1" pageScale="1" pageWidth="827" pageHeight="1169" math="0" shadow="0"> <root> <mxCell id="0" /> <mxCell id="1" parent="0" /> <mxCell id="KFZwfhmbditGVcSo1DL3-1" value="&lt;div&gt;&lt;br&gt;&lt;/div&gt;&lt;pre style=&quot;margin-top: 0px; background-color: var(--vscode-textCodeBlock-background); border: 1px solid var(--vscode-widget-border); padding: 16px; border-radius: 3px; overflow: auto; white-space: pre-wrap; color: rgb(218, 218, 218); font-size: 14px; font-style: normal; font-variant-ligatures: normal; font-variant-caps: normal; font-weight: 400; letter-spacing: normal; orphans: 2; text-align: start; text-indent: 0px; text-transform: none; widows: 2; word-spacing: 0px; -webkit-text-stroke-width: 0px; text-decoration-thickness: initial; text-decoration-style: initial; text-decoration-color: initial;&quot;&gt;&lt;code style=&quot;font-family: var(--vscode-editor-font-family, &amp;quot;SF Mono&amp;quot;, Monaco, Menlo, Consolas, &amp;quot;Ubuntu Mono&amp;quot;, &amp;quot;Liberation Mono&amp;quot;, &amp;quot;DejaVu Sans Mono&amp;quot;, &amp;quot;Courier New&amp;quot;, monospace); color: var(--vscode-editor-foreground); background: none; padding: 0px; border-radius: 4px; font-size: 1em; line-height: 1.357em; display: inline-block; tab-size: 4; position: relative;&quot; dir=&quot;auto&quot; class=&quot;code-line language-yaml&quot; data-line=&quot;45&quot;&gt;&lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;&lt;br&gt;&lt;/span&gt;&lt;/code&gt;&lt;font color=&quot;#d69d85&quot;&gt;&lt;code style=&quot;font-family: var(--vscode-editor-font-family, &amp;quot;SF Mono&amp;quot;, Monaco, Menlo, Consolas, &amp;quot;Ubuntu Mono&amp;quot;, &amp;quot;Liberation Mono&amp;quot;, &amp;quot;DejaVu Sans Mono&amp;quot;, &amp;quot;Courier New&amp;quot;, monospace); background: none; padding: 0px; border-radius: 4px; font-size: 1em; line-height: 1.357em; display: inline-block; tab-size: 4; position: relative;&quot; dir=&quot;auto&quot; class=&quot;code-line language-yaml&quot; data-line=&quot;45&quot;&gt;&lt;/code&gt;&lt;/font&gt;&lt;code style=&quot;font-family: var(--vscode-editor-font-family, &amp;quot;SF Mono&amp;quot;, Monaco, Menlo, Consolas, &amp;quot;Ubuntu Mono&amp;quot;, &amp;quot;Liberation Mono&amp;quot;, &amp;quot;DejaVu Sans Mono&amp;quot;, &amp;quot;Courier New&amp;quot;, monospace); color: var(--vscode-editor-foreground); background: none; padding: 0px; border-radius: 4px; font-size: 1em; line-height: 1.357em; display: inline-block; tab-size: 4; position: relative;&quot; dir=&quot;auto&quot; class=&quot;code-line language-yaml&quot; data-line=&quot;45&quot;&gt;&lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;&lt;br&gt;&lt;/span&gt;&lt;/code&gt;&lt;code style=&quot;font-family: var(--vscode-editor-font-family, &amp;quot;SF Mono&amp;quot;, Monaco, Menlo, Consolas, &amp;quot;Ubuntu Mono&amp;quot;, &amp;quot;Liberation Mono&amp;quot;, &amp;quot;DejaVu Sans Mono&amp;quot;, &amp;quot;Courier New&amp;quot;, monospace); color: var(--vscode-editor-foreground); background: none; padding: 0px; border-radius: 4px; font-size: 1em; line-height: 1.357em; display: inline-block; tab-size: 4; position: relative;&quot; dir=&quot;auto&quot; class=&quot;code-line language-yaml&quot; data-line=&quot;45&quot;&gt;&lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;&lt;br&gt;requirements:&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;example-01-01&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;validators:&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;name:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;mapping.crosswalk.missing_regulatory_elements&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;name:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;mapping.crosswalk.regulatory_element_details&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;example-01-02&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;validators:&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;name:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;mapping.traffic_light.missing_regulatory_elements&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;name:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;mapping.traffic_light.regulatory_element_details&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;example-01-03&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;validators:&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;name:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;mapping.stop_line.missing_regulatory_elements&lt;/span&gt;&lt;/code&gt;&lt;/pre&gt;" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;fillColor=#241f31;" vertex="1" parent="1"> <mxGeometry x="-800" y="400" width="510" height="300" as="geometry" /> </mxCell> <mxCell id="KFZwfhmbditGVcSo1DL3-2" value="&lt;pre style=&quot;margin-top: 0px; background-color: var(--vscode-textCodeBlock-background); border: 1px solid var(--vscode-widget-border); padding: 16px; border-radius: 3px; overflow: auto; white-space: pre-wrap; color: rgb(218, 218, 218); font-size: 14px; font-style: normal; font-variant-ligatures: normal; font-variant-caps: normal; font-weight: 400; letter-spacing: normal; orphans: 2; text-align: start; text-indent: 0px; text-transform: none; widows: 2; word-spacing: 0px; -webkit-text-stroke-width: 0px; text-decoration-thickness: initial; text-decoration-style: initial; text-decoration-color: initial;&quot;&gt;&lt;code style=&quot;font-family: var(--vscode-editor-font-family, &amp;quot;SF Mono&amp;quot;, Monaco, Menlo, Consolas, &amp;quot;Ubuntu Mono&amp;quot;, &amp;quot;Liberation Mono&amp;quot;, &amp;quot;DejaVu Sans Mono&amp;quot;, &amp;quot;Courier New&amp;quot;, monospace); color: var(--vscode-editor-foreground); background: none; padding: 0px; border-radius: 4px; font-size: 1em; line-height: 1.357em; display: inline-block; tab-size: 4; position: relative;&quot; dir=&quot;auto&quot; class=&quot;code-line language-yaml&quot; data-line=&quot;45&quot;&gt;&lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;&lt;br&gt;&lt;/span&gt;&lt;/code&gt;&lt;font color=&quot;#d69d85&quot;&gt;&lt;code style=&quot;font-family: var(--vscode-editor-font-family, &amp;quot;SF Mono&amp;quot;, Monaco, Menlo, Consolas, &amp;quot;Ubuntu Mono&amp;quot;, &amp;quot;Liberation Mono&amp;quot;, &amp;quot;DejaVu Sans Mono&amp;quot;, &amp;quot;Courier New&amp;quot;, monospace); background: none; padding: 0px; border-radius: 4px; font-size: 1em; line-height: 1.357em; display: inline-block; tab-size: 4; position: relative;&quot; dir=&quot;auto&quot; class=&quot;code-line language-yaml&quot; data-line=&quot;45&quot;&gt;&lt;span class=&quot;hljs-attr&quot;&gt;&lt;br&gt;&lt;/span&gt;&lt;/code&gt;&lt;/font&gt;&lt;code style=&quot;font-family: var(--vscode-editor-font-family, &amp;quot;SF Mono&amp;quot;, Monaco, Menlo, Consolas, &amp;quot;Ubuntu Mono&amp;quot;, &amp;quot;Liberation Mono&amp;quot;, &amp;quot;DejaVu Sans Mono&amp;quot;, &amp;quot;Courier New&amp;quot;, monospace); color: var(--vscode-editor-foreground); background: none; padding: 0px; border-radius: 4px; font-size: 1em; line-height: 1.357em; display: inline-block; tab-size: 4; position: relative;&quot; dir=&quot;auto&quot; class=&quot;code-line language-yaml&quot; data-line=&quot;76&quot;&gt;&lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;requirements:&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;example-01-01&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;passed:&lt;/span&gt; &lt;span style=&quot;color: rgb(86, 156, 214);&quot; class=&quot;hljs-literal&quot;&gt;false&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;validators:&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;name:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;mapping.crosswalk.missing_regulatory_elements&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;passed:&lt;/span&gt; &lt;span style=&quot;color: rgb(86, 156, 214);&quot; class=&quot;hljs-literal&quot;&gt;false&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;issues:&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;severity:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;Error&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;primitive:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;lanelet&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(184, 215, 163);&quot; class=&quot;hljs-number&quot;&gt;163&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;message:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;No regulatory&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;element&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;refers&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;to&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;this&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;crosswalk.&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;severity:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;Error&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;primitive:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;lanelet&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(184, 215, 163);&quot; class=&quot;hljs-number&quot;&gt;164&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;message:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;No regulatory&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;element&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;refers&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;to&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;this&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;crosswalk.&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;severity:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;Error&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;primitive:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;lanelet&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(184, 215, 163);&quot; class=&quot;hljs-number&quot;&gt;165&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;message:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;No regulatory&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;element&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;refers&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;to&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;this&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;crosswalk.&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;severity:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;Error&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;primitive:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;lanelet&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(184, 215, 163);&quot; class=&quot;hljs-number&quot;&gt;166&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;message:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;No regulatory&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;element&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;refers&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;to&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;this&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;crosswalk.&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;name:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;mapping.crosswalk.regulatory_element_details&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;passed:&lt;/span&gt; &lt;span style=&quot;color: rgb(86, 156, 214);&quot; class=&quot;hljs-literal&quot;&gt;true&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;example-01-02&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;passed:&lt;/span&gt; &lt;span style=&quot;color: rgb(86, 156, 214);&quot; class=&quot;hljs-literal&quot;&gt;false&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;validators:&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;name:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;mapping.traffic_light.missing_regulatory_elements&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;passed:&lt;/span&gt; &lt;span style=&quot;color: rgb(86, 156, 214);&quot; class=&quot;hljs-literal&quot;&gt;true&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;name:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;mapping.traffic_light.regulatory_element_details&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;passed:&lt;/span&gt; &lt;span style=&quot;color: rgb(86, 156, 214);&quot; class=&quot;hljs-literal&quot;&gt;false&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;issues:&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;severity:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;Error&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;primitive:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;regulatory&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;element&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(184, 215, 163);&quot; class=&quot;hljs-number&quot;&gt;9896&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;message:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;Regulatory&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;element&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;of&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;traffic&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;light&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;must&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;have&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;a&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;stop&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;line(ref_line).&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;severity:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;Error&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;primitive:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;regulatory&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;element&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(184, 215, 163);&quot; class=&quot;hljs-number&quot;&gt;9918&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;message:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;Regulatory&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;element&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;of&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;traffic&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;light&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;must&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;have&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;a&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;stop&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;line(ref_line).&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;severity:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;Error&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;primitive:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;regulatory&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;element&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(184, 215, 163);&quot; class=&quot;hljs-number&quot;&gt;9838&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;message:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;Regulatory&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;element&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;of&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;traffic&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;light&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;must&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;have&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;a&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;stop&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;line(ref_line).&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;severity:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;Error&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;primitive:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;regulatory&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;element&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(184, 215, 163);&quot; class=&quot;hljs-number&quot;&gt;9874&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;message:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;Regulatory&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;element&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;of&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;traffic&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;light&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;must&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;have&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;a&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;stop&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;line(ref_line).&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;example-01-03&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;passed:&lt;/span&gt; &lt;span style=&quot;color: rgb(86, 156, 214);&quot; class=&quot;hljs-literal&quot;&gt;true&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;validators:&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;name:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;mapping.stop_line.missing_regulatory_elements&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;passed:&lt;/span&gt; &lt;span style=&quot;color: rgb(86, 156, 214);&quot; class=&quot;hljs-literal&quot;&gt;true&lt;/span&gt;&lt;/code&gt;&lt;/pre&gt;" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;fillColor=#241F31;" vertex="1" parent="1"> <mxGeometry x="-190" y="400" width="660" height="1090" as="geometry" /> </mxCell> <mxCell id="Nch5D1Gedkqk2BCtd5IL-1" value="&lt;div align=&quot;left&quot;&gt;&lt;font style=&quot;font-size: 18px;&quot;&gt;input_requirement_set.yaml&lt;/font&gt;&lt;/div&gt;" style="text;html=1;align=left;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="1"> <mxGeometry x="-800" y="370" width="250" height="20" as="geometry" /> </mxCell> <mxCell id="Nch5D1Gedkqk2BCtd5IL-2" value="&lt;div align=&quot;left&quot;&gt;&lt;font style=&quot;font-size: 18px;&quot;&gt;lanelet2_validation_results.yaml&lt;/font&gt;&lt;/div&gt;" style="text;html=1;align=left;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="1"> <mxGeometry x="-190" y="370" width="250" height="20" as="geometry" /> </mxCell> <mxCell id="Nch5D1Gedkqk2BCtd5IL-5" value="&lt;font color=&quot;#9cdcfe&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;requirements:&lt;/font&gt;&lt;font color=&quot;#d69d85&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;&lt;br&gt;&amp;nbsp; - &lt;/font&gt;&lt;font color=&quot;#ccffff&quot;&gt;&lt;/font&gt;&lt;font color=&quot;#9cdcfe&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;id:&lt;/font&gt;&lt;font color=&quot;#d69d85&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt; example-01-01&lt;br&gt;&amp;nbsp;&amp;nbsp;&amp;nbsp; &lt;/font&gt;&lt;font color=&quot;#ccffff&quot;&gt;&lt;/font&gt;&lt;font color=&quot;#9cdcfe&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;validators:&lt;/font&gt;&lt;font color=&quot;#d69d85&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;&lt;br&gt;&amp;nbsp;&amp;nbsp;&amp;nbsp;&amp;nbsp;&amp;nbsp; - &lt;/font&gt;&lt;font color=&quot;#9cdcfe&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;name:&lt;/font&gt;&lt;font color=&quot;#d69d85&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt; mapping.crosswalk.missing_regulatory_elements&lt;br&gt;&amp;nbsp;&amp;nbsp;&amp;nbsp;&amp;nbsp;&amp;nbsp; - &lt;/font&gt;&lt;font color=&quot;#9cdcfe&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;name:&lt;/font&gt;&lt;font color=&quot;#d69d85&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt; mapping.crosswalk.regulatory_element_details&lt;br&gt;&amp;nbsp; - &lt;/font&gt;&lt;font color=&quot;#9cdcfe&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;id:&lt;/font&gt;&lt;font color=&quot;#d69d85&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt; example-01-02&lt;br&gt;&amp;nbsp;&amp;nbsp;&amp;nbsp; &lt;/font&gt;&lt;font color=&quot;#9cdcfe&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;validators:&lt;/font&gt;&lt;font color=&quot;#d69d85&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;&lt;br&gt;&amp;nbsp;&amp;nbsp;&amp;nbsp;&amp;nbsp;&amp;nbsp; - &lt;/font&gt;&lt;font color=&quot;#9cdcfe&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;name:&lt;/font&gt;&lt;font color=&quot;#d69d85&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt; mapping.traffic_light.missing_regulatory_elements&lt;br&gt;&amp;nbsp;&amp;nbsp;&amp;nbsp;&amp;nbsp;&amp;nbsp; - &lt;/font&gt;&lt;font color=&quot;#9cdcfe&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;name:&lt;/font&gt;&lt;font color=&quot;#d69d85&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt; mapping.traffic_light.regulatory_element_details&lt;br&gt;&amp;nbsp; - &lt;/font&gt;&lt;font color=&quot;#9cdcfe&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;id:&lt;/font&gt;&lt;font color=&quot;#d69d85&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt; example-01-03&lt;br&gt;&amp;nbsp;&amp;nbsp;&amp;nbsp; &lt;/font&gt;&lt;font color=&quot;#9cdcfe&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;validators:&lt;/font&gt;&lt;font color=&quot;#d69d85&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;&lt;br&gt;&amp;nbsp;&amp;nbsp;&amp;nbsp;&amp;nbsp;&amp;nbsp; - &lt;/font&gt;&lt;font color=&quot;#9cdcfe&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;name:&lt;/font&gt;&lt;font color=&quot;#d69d85&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt; mapping.stop_line.missing_regulatory_elements&lt;/font&gt;" style="text;html=1;align=left;verticalAlign=middle;whiteSpace=wrap;rounded=0;fillColor=#241F31;" vertex="1" parent="1"> <mxGeometry x="-800" y="770" width="540" height="270" as="geometry" /> </mxCell> </root> </mxGraphModel> </diagram> </mxfile> " + content="<mxfile host="app.diagrams.net" agent="Mozilla/5.0 (X11; Ubuntu; Linux x86_64; rv:131.0) Gecko/20100101 Firefox/131.0" version="24.7.17" pages="3" scale="1" border="0"> <diagram name="ページ1" id="txHnBQ8Bwk_QwKYoOu-f"> <mxGraphModel dx="2744" dy="1067" grid="1" gridSize="10" guides="1" tooltips="1" connect="1" arrows="1" fold="1" page="1" pageScale="1" pageWidth="827" pageHeight="1169" math="0" shadow="0"> <root> <mxCell id="0" /> <mxCell id="1" parent="0" /> <mxCell id="5tm8MCw5WYpOVBz9AR-8-2" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=1;exitY=0.25;exitDx=0;exitDy=0;entryX=0;entryY=0.5;entryDx=0;entryDy=0;" parent="1" source="pZbjCYV6troIvum8nigY-1" target="8BQUtLSBopQVORKjeofY-4" edge="1"> <mxGeometry relative="1" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-1" value="autoware_lanelet2_map_validator" style="rounded=1;whiteSpace=wrap;html=1;strokeColor=#FF0000;strokeWidth=5;" parent="1" vertex="1"> <mxGeometry x="-560" y="75" width="260" height="100" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-21" value="" style="shape=callout;whiteSpace=wrap;html=1;perimeter=calloutPerimeter;rotation=-180;position2=0.55;fillColor=#FFEEF0;strokeColor=#FF0000;size=50;position=0.5;" parent="1" vertex="1"> <mxGeometry x="-730" y="180" width="660" height="310" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-5" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=0;exitY=0;exitDx=150;exitDy=35;exitPerimeter=0;entryX=0;entryY=0.25;entryDx=0;entryDy=0;" parent="1" source="pZbjCYV6troIvum8nigY-2" target="pZbjCYV6troIvum8nigY-1" edge="1"> <mxGeometry relative="1" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-2" value="lanelet2_map.osm" style="shape=note;whiteSpace=wrap;html=1;backgroundOutline=1;darkOpacity=0.05;size=15;fillColor=#fff2cc;strokeColor=#8C7738;" parent="1" vertex="1"> <mxGeometry x="-750" y="50" width="150" height="55" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-6" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=0;exitY=0;exitDx=150;exitDy=35;exitPerimeter=0;entryX=0;entryY=0.75;entryDx=0;entryDy=0;dashed=1;" parent="1" source="pZbjCYV6troIvum8nigY-3" target="pZbjCYV6troIvum8nigY-1" edge="1"> <mxGeometry relative="1" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-3" value="requirement_set.json" style="shape=note;whiteSpace=wrap;html=1;backgroundOutline=1;darkOpacity=0.05;size=15;fillColor=#fff2cc;strokeColor=#8C7738;" parent="1" vertex="1"> <mxGeometry x="-750" y="140" width="150" height="55" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-4" value="lanelet2_validation_results.json" style="shape=note;whiteSpace=wrap;html=1;backgroundOutline=1;darkOpacity=0.05;size=15;fillColor=#CCFFFF;strokeColor=#8C7738;" parent="1" vertex="1"> <mxGeometry x="-260" y="142" width="210" height="53" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-8" value="&lt;b&gt;traffic light&lt;/b&gt;" style="swimlane;fontStyle=0;childLayout=stackLayout;horizontal=1;startSize=30;horizontalStack=0;resizeParent=1;resizeParentMax=0;resizeLast=0;collapsible=1;marginBottom=0;whiteSpace=wrap;html=1;" parent="1" vertex="1"> <mxGeometry x="-705" y="350" width="300" height="120" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-9" value="- mapping.traffic_light.missing_regulatory_elements" style="text;align=left;verticalAlign=middle;spacingLeft=4;spacingRight=4;overflow=hidden;points=[[0,0.5],[1,0.5]];portConstraint=eastwest;rotatable=0;whiteSpace=wrap;html=1;fillColor=default;strokeColor=default;" parent="pZbjCYV6troIvum8nigY-8" vertex="1"> <mxGeometry y="30" width="300" height="30" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-10" value="- mapping.traffic_light.regulatory_element_details" style="text;align=left;verticalAlign=middle;spacingLeft=4;spacingRight=4;overflow=hidden;points=[[0,0.5],[1,0.5]];portConstraint=eastwest;rotatable=0;whiteSpace=wrap;html=1;fillColor=default;strokeColor=default;" parent="pZbjCYV6troIvum8nigY-8" vertex="1"> <mxGeometry y="60" width="300" height="30" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-27" value="- &lt;i&gt;and more...&lt;/i&gt;" style="text;align=left;verticalAlign=middle;spacingLeft=4;spacingRight=4;overflow=hidden;points=[[0,0.5],[1,0.5]];portConstraint=eastwest;rotatable=0;whiteSpace=wrap;html=1;fillColor=default;strokeColor=default;" parent="pZbjCYV6troIvum8nigY-8" vertex="1"> <mxGeometry y="90" width="300" height="30" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-17" value="&lt;b&gt;crosswalk&lt;/b&gt;" style="swimlane;fontStyle=0;childLayout=stackLayout;horizontal=1;startSize=30;horizontalStack=0;resizeParent=1;resizeParentMax=0;resizeLast=0;collapsible=1;marginBottom=0;whiteSpace=wrap;html=1;" parent="1" vertex="1"> <mxGeometry x="-395" y="250" width="300" height="120" as="geometry"> <mxRectangle x="-465" y="730" width="100" height="30" as="alternateBounds" /> </mxGeometry> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-18" value="- mapping.crosswalk.missing_regulatory_elements" style="text;align=left;verticalAlign=middle;spacingLeft=4;spacingRight=4;overflow=hidden;points=[[0,0.5],[1,0.5]];portConstraint=eastwest;rotatable=0;whiteSpace=wrap;html=1;fillColor=default;strokeColor=default;" parent="pZbjCYV6troIvum8nigY-17" vertex="1"> <mxGeometry y="30" width="300" height="30" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-19" value="- mapping.crosswalk.regulatory_element_details" style="text;align=left;verticalAlign=middle;spacingLeft=4;spacingRight=4;overflow=hidden;points=[[0,0.5],[1,0.5]];portConstraint=eastwest;rotatable=0;whiteSpace=wrap;html=1;fillColor=default;strokeColor=default;" parent="pZbjCYV6troIvum8nigY-17" vertex="1"> <mxGeometry y="60" width="300" height="30" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-28" value="- &lt;i&gt;and more...&lt;/i&gt;" style="text;align=left;verticalAlign=middle;spacingLeft=4;spacingRight=4;overflow=hidden;points=[[0,0.5],[1,0.5]];portConstraint=eastwest;rotatable=0;whiteSpace=wrap;html=1;fillColor=default;strokeColor=default;" parent="pZbjCYV6troIvum8nigY-17" vertex="1"> <mxGeometry y="90" width="300" height="30" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-13" value="&lt;b&gt;stop line&lt;/b&gt;" style="swimlane;fontStyle=0;childLayout=stackLayout;horizontal=1;startSize=30;horizontalStack=0;resizeParent=1;resizeParentMax=0;resizeLast=0;collapsible=1;marginBottom=0;whiteSpace=wrap;html=1;" parent="1" vertex="1"> <mxGeometry x="-705" y="250" width="300" height="90" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-14" value="&lt;font face=&quot;Helvetica&quot;&gt;- mapping.stop_line.missing_regulatory_elements&lt;/font&gt;" style="text;align=left;verticalAlign=middle;spacingLeft=4;spacingRight=4;overflow=hidden;points=[[0,0.5],[1,0.5]];portConstraint=eastwest;rotatable=0;whiteSpace=wrap;html=1;fillColor=default;strokeColor=default;" parent="pZbjCYV6troIvum8nigY-13" vertex="1"> <mxGeometry y="30" width="300" height="30" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-26" value="&lt;font face=&quot;Helvetica&quot;&gt;- &lt;i&gt;and more...&lt;br&gt;&lt;/i&gt;&lt;/font&gt;" style="text;align=left;verticalAlign=middle;spacingLeft=4;spacingRight=4;overflow=hidden;points=[[0,0.5],[1,0.5]];portConstraint=eastwest;rotatable=0;whiteSpace=wrap;html=1;fillColor=default;strokeColor=default;" parent="pZbjCYV6troIvum8nigY-13" vertex="1"> <mxGeometry y="60" width="300" height="30" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-22" value="autoware_lanelet2_map_validator contains a bunch of validators, and calls the ones written in the requirement_set.yaml" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;fontStyle=2;fillColor=default;opacity=70;" parent="1" vertex="1"> <mxGeometry x="-380" y="420" width="270" height="50" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-23" value="&lt;font style=&quot;font-size: 18px;&quot;&gt;Input&lt;/font&gt;" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;fontStyle=1" parent="1" vertex="1"> <mxGeometry x="-705" y="10" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-24" value="&lt;font style=&quot;font-size: 18px;&quot;&gt;Output&lt;/font&gt;" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;fontStyle=1" parent="1" vertex="1"> <mxGeometry x="-185" y="10" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="pZbjCYV6troIvum8nigY-29" value="&lt;b&gt;&lt;i&gt;and more other categories...&lt;br&gt;&lt;/i&gt;&lt;/b&gt;" style="swimlane;fontStyle=0;childLayout=stackLayout;horizontal=1;startSize=30;horizontalStack=0;resizeParent=1;resizeParentMax=0;resizeLast=0;collapsible=1;marginBottom=0;whiteSpace=wrap;html=1;" parent="1" vertex="1" collapsed="1"> <mxGeometry x="-342.5" y="380" width="195" height="30" as="geometry"> <mxRectangle x="-465" y="860" width="300" height="60" as="alternateBounds" /> </mxGeometry> </mxCell> <mxCell id="8BQUtLSBopQVORKjeofY-4" value="&lt;font color=&quot;#b3ff66&quot;&gt;console output&lt;/font&gt;" style="rounded=0;whiteSpace=wrap;html=1;strokeColor=#E6E6E6;fillColor=#241F31;" parent="1" vertex="1"> <mxGeometry x="-260" y="50" width="210" height="53" as="geometry" /> </mxCell> <mxCell id="5tm8MCw5WYpOVBz9AR-8-1" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=1;exitY=0.75;exitDx=0;exitDy=0;entryX=0;entryY=0.5;entryDx=0;entryDy=0;entryPerimeter=0;dashed=1;" parent="1" source="pZbjCYV6troIvum8nigY-1" target="pZbjCYV6troIvum8nigY-4" edge="1"> <mxGeometry relative="1" as="geometry" /> </mxCell> <mxCell id="5tm8MCw5WYpOVBz9AR-8-3" value="&lt;font style=&quot;font-size: 10px;&quot;&gt;&lt;i&gt;Only if a requirement set input is given&lt;/i&gt;&lt;/font&gt;" style="text;html=1;align=right;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="-275" y="190" width="220" height="25" as="geometry" /> </mxCell> <mxCell id="5tm8MCw5WYpOVBz9AR-8-4" value="&lt;font style=&quot;font-size: 10px;&quot;&gt;&lt;i&gt;Optional, but recommended&lt;br&gt;&lt;/i&gt;&lt;/font&gt;" style="text;html=1;align=right;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1"> <mxGeometry x="-750" y="190" width="150" height="25" as="geometry" /> </mxCell> </root> </mxGraphModel> </diagram> <diagram id="Y81l0PrR7Q6dCZwbgd-N" name="ページ2"> <mxGraphModel dx="3140" dy="1288" grid="1" gridSize="10" guides="1" tooltips="1" connect="1" arrows="1" fold="1" page="1" pageScale="1" pageWidth="827" pageHeight="1169" math="0" shadow="0"> <root> <mxCell id="0" /> <mxCell id="1" parent="0" /> <mxCell id="KFZwfhmbditGVcSo1DL3-1" value="&lt;div&gt;&lt;br&gt;&lt;/div&gt;&lt;pre style=&quot;margin-top: 0px; background-color: var(--vscode-textCodeBlock-background); border: 1px solid var(--vscode-widget-border); padding: 16px; border-radius: 3px; overflow: auto; white-space: pre-wrap; color: rgb(218, 218, 218); font-size: 14px; font-style: normal; font-variant-ligatures: normal; font-variant-caps: normal; font-weight: 400; letter-spacing: normal; orphans: 2; text-align: start; text-indent: 0px; text-transform: none; widows: 2; word-spacing: 0px; -webkit-text-stroke-width: 0px; text-decoration-thickness: initial; text-decoration-style: initial; text-decoration-color: initial;&quot;&gt;&lt;code style=&quot;font-family: var(--vscode-editor-font-family, &amp;quot;SF Mono&amp;quot;, Monaco, Menlo, Consolas, &amp;quot;Ubuntu Mono&amp;quot;, &amp;quot;Liberation Mono&amp;quot;, &amp;quot;DejaVu Sans Mono&amp;quot;, &amp;quot;Courier New&amp;quot;, monospace); color: var(--vscode-editor-foreground); background: none; padding: 0px; border-radius: 4px; font-size: 1em; line-height: 1.357em; display: inline-block; tab-size: 4; position: relative;&quot; dir=&quot;auto&quot; class=&quot;code-line language-yaml&quot; data-line=&quot;45&quot;&gt;&lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;&lt;br&gt;&lt;/span&gt;&lt;/code&gt;&lt;font color=&quot;#d69d85&quot;&gt;&lt;code style=&quot;font-family: var(--vscode-editor-font-family, &amp;quot;SF Mono&amp;quot;, Monaco, Menlo, Consolas, &amp;quot;Ubuntu Mono&amp;quot;, &amp;quot;Liberation Mono&amp;quot;, &amp;quot;DejaVu Sans Mono&amp;quot;, &amp;quot;Courier New&amp;quot;, monospace); background: none; padding: 0px; border-radius: 4px; font-size: 1em; line-height: 1.357em; display: inline-block; tab-size: 4; position: relative;&quot; dir=&quot;auto&quot; class=&quot;code-line language-yaml&quot; data-line=&quot;45&quot;&gt;&lt;/code&gt;&lt;/font&gt;&lt;code style=&quot;font-family: var(--vscode-editor-font-family, &amp;quot;SF Mono&amp;quot;, Monaco, Menlo, Consolas, &amp;quot;Ubuntu Mono&amp;quot;, &amp;quot;Liberation Mono&amp;quot;, &amp;quot;DejaVu Sans Mono&amp;quot;, &amp;quot;Courier New&amp;quot;, monospace); color: var(--vscode-editor-foreground); background: none; padding: 0px; border-radius: 4px; font-size: 1em; line-height: 1.357em; display: inline-block; tab-size: 4; position: relative;&quot; dir=&quot;auto&quot; class=&quot;code-line language-yaml&quot; data-line=&quot;45&quot;&gt;&lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;&lt;br&gt;&lt;/span&gt;&lt;/code&gt;&lt;code style=&quot;font-family: var(--vscode-editor-font-family, &amp;quot;SF Mono&amp;quot;, Monaco, Menlo, Consolas, &amp;quot;Ubuntu Mono&amp;quot;, &amp;quot;Liberation Mono&amp;quot;, &amp;quot;DejaVu Sans Mono&amp;quot;, &amp;quot;Courier New&amp;quot;, monospace); color: var(--vscode-editor-foreground); background: none; padding: 0px; border-radius: 4px; font-size: 1em; line-height: 1.357em; display: inline-block; tab-size: 4; position: relative;&quot; dir=&quot;auto&quot; class=&quot;code-line language-yaml&quot; data-line=&quot;45&quot;&gt;&lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;&lt;br&gt;requirements:&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;example-01-01&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;validators:&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;name:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;mapping.crosswalk.missing_regulatory_elements&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;name:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;mapping.crosswalk.regulatory_element_details&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;example-01-02&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;validators:&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;name:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;mapping.traffic_light.missing_regulatory_elements&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;name:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;mapping.traffic_light.regulatory_element_details&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;example-01-03&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;validators:&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;name:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;mapping.stop_line.missing_regulatory_elements&lt;/span&gt;&lt;/code&gt;&lt;/pre&gt;" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;fillColor=#241f31;" vertex="1" parent="1"> <mxGeometry x="-800" y="400" width="510" height="300" as="geometry" /> </mxCell> <mxCell id="KFZwfhmbditGVcSo1DL3-2" value="&lt;pre style=&quot;margin-top: 0px; background-color: var(--vscode-textCodeBlock-background); border: 1px solid var(--vscode-widget-border); padding: 16px; border-radius: 3px; overflow: auto; white-space: pre-wrap; color: rgb(218, 218, 218); font-size: 14px; font-style: normal; font-variant-ligatures: normal; font-variant-caps: normal; font-weight: 400; letter-spacing: normal; orphans: 2; text-align: start; text-indent: 0px; text-transform: none; widows: 2; word-spacing: 0px; -webkit-text-stroke-width: 0px; text-decoration-thickness: initial; text-decoration-style: initial; text-decoration-color: initial;&quot;&gt;&lt;code style=&quot;font-family: var(--vscode-editor-font-family, &amp;quot;SF Mono&amp;quot;, Monaco, Menlo, Consolas, &amp;quot;Ubuntu Mono&amp;quot;, &amp;quot;Liberation Mono&amp;quot;, &amp;quot;DejaVu Sans Mono&amp;quot;, &amp;quot;Courier New&amp;quot;, monospace); color: var(--vscode-editor-foreground); background: none; padding: 0px; border-radius: 4px; font-size: 1em; line-height: 1.357em; display: inline-block; tab-size: 4; position: relative;&quot; dir=&quot;auto&quot; class=&quot;code-line language-yaml&quot; data-line=&quot;45&quot;&gt;&lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;&lt;br&gt;&lt;/span&gt;&lt;/code&gt;&lt;font color=&quot;#d69d85&quot;&gt;&lt;code style=&quot;font-family: var(--vscode-editor-font-family, &amp;quot;SF Mono&amp;quot;, Monaco, Menlo, Consolas, &amp;quot;Ubuntu Mono&amp;quot;, &amp;quot;Liberation Mono&amp;quot;, &amp;quot;DejaVu Sans Mono&amp;quot;, &amp;quot;Courier New&amp;quot;, monospace); background: none; padding: 0px; border-radius: 4px; font-size: 1em; line-height: 1.357em; display: inline-block; tab-size: 4; position: relative;&quot; dir=&quot;auto&quot; class=&quot;code-line language-yaml&quot; data-line=&quot;45&quot;&gt;&lt;span class=&quot;hljs-attr&quot;&gt;&lt;br&gt;&lt;/span&gt;&lt;/code&gt;&lt;/font&gt;&lt;code style=&quot;font-family: var(--vscode-editor-font-family, &amp;quot;SF Mono&amp;quot;, Monaco, Menlo, Consolas, &amp;quot;Ubuntu Mono&amp;quot;, &amp;quot;Liberation Mono&amp;quot;, &amp;quot;DejaVu Sans Mono&amp;quot;, &amp;quot;Courier New&amp;quot;, monospace); color: var(--vscode-editor-foreground); background: none; padding: 0px; border-radius: 4px; font-size: 1em; line-height: 1.357em; display: inline-block; tab-size: 4; position: relative;&quot; dir=&quot;auto&quot; class=&quot;code-line language-yaml&quot; data-line=&quot;76&quot;&gt;&lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;requirements:&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;example-01-01&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;passed:&lt;/span&gt; &lt;span style=&quot;color: rgb(86, 156, 214);&quot; class=&quot;hljs-literal&quot;&gt;false&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;validators:&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;name:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;mapping.crosswalk.missing_regulatory_elements&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;passed:&lt;/span&gt; &lt;span style=&quot;color: rgb(86, 156, 214);&quot; class=&quot;hljs-literal&quot;&gt;false&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;issues:&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;severity:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;Error&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;primitive:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;lanelet&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(184, 215, 163);&quot; class=&quot;hljs-number&quot;&gt;163&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;message:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;No regulatory&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;element&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;refers&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;to&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;this&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;crosswalk.&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;severity:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;Error&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;primitive:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;lanelet&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(184, 215, 163);&quot; class=&quot;hljs-number&quot;&gt;164&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;message:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;No regulatory&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;element&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;refers&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;to&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;this&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;crosswalk.&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;severity:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;Error&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;primitive:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;lanelet&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(184, 215, 163);&quot; class=&quot;hljs-number&quot;&gt;165&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;message:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;No regulatory&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;element&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;refers&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;to&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;this&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;crosswalk.&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;severity:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;Error&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;primitive:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;lanelet&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(184, 215, 163);&quot; class=&quot;hljs-number&quot;&gt;166&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;message:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;No regulatory&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;element&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;refers&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;to&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;this&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;crosswalk.&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;name:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;mapping.crosswalk.regulatory_element_details&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;passed:&lt;/span&gt; &lt;span style=&quot;color: rgb(86, 156, 214);&quot; class=&quot;hljs-literal&quot;&gt;true&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;example-01-02&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;passed:&lt;/span&gt; &lt;span style=&quot;color: rgb(86, 156, 214);&quot; class=&quot;hljs-literal&quot;&gt;false&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;validators:&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;name:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;mapping.traffic_light.missing_regulatory_elements&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;passed:&lt;/span&gt; &lt;span style=&quot;color: rgb(86, 156, 214);&quot; class=&quot;hljs-literal&quot;&gt;true&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;name:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;mapping.traffic_light.regulatory_element_details&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;passed:&lt;/span&gt; &lt;span style=&quot;color: rgb(86, 156, 214);&quot; class=&quot;hljs-literal&quot;&gt;false&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;issues:&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;severity:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;Error&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;primitive:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;regulatory&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;element&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(184, 215, 163);&quot; class=&quot;hljs-number&quot;&gt;9896&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;message:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;Regulatory&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;element&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;of&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;traffic&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;light&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;must&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;have&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;a&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;stop&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;line(ref_line).&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;severity:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;Error&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;primitive:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;regulatory&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;element&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(184, 215, 163);&quot; class=&quot;hljs-number&quot;&gt;9918&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;message:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;Regulatory&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;element&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;of&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;traffic&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;light&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;must&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;have&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;a&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;stop&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;line(ref_line).&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;severity:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;Error&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;primitive:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;regulatory&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;element&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(184, 215, 163);&quot; class=&quot;hljs-number&quot;&gt;9838&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;message:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;Regulatory&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;element&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;of&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;traffic&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;light&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;must&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;have&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;a&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;stop&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;line(ref_line).&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;severity:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;Error&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;primitive:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;regulatory&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;element&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(184, 215, 163);&quot; class=&quot;hljs-number&quot;&gt;9874&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;message:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;Regulatory&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;element&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;of&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;traffic&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;light&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;must&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;have&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;a&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;stop&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;line(ref_line).&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;id:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;example-01-03&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;passed:&lt;/span&gt; &lt;span style=&quot;color: rgb(86, 156, 214);&quot; class=&quot;hljs-literal&quot;&gt;true&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;validators:&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(215, 186, 125);&quot; class=&quot;hljs-bullet&quot;&gt;-&lt;/span&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;name:&lt;/span&gt; &lt;span style=&quot;color: rgb(214, 157, 133);&quot; class=&quot;hljs-string&quot;&gt;mapping.stop_line.missing_regulatory_elements&lt;/span&gt;&lt;br&gt; &lt;span style=&quot;color: rgb(156, 220, 254);&quot; class=&quot;hljs-attr&quot;&gt;passed:&lt;/span&gt; &lt;span style=&quot;color: rgb(86, 156, 214);&quot; class=&quot;hljs-literal&quot;&gt;true&lt;/span&gt;&lt;/code&gt;&lt;/pre&gt;" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;fillColor=#241F31;" vertex="1" parent="1"> <mxGeometry x="-190" y="400" width="660" height="1090" as="geometry" /> </mxCell> <mxCell id="Nch5D1Gedkqk2BCtd5IL-1" value="&lt;div align=&quot;left&quot;&gt;&lt;font style=&quot;font-size: 18px;&quot;&gt;input_requirement_set.yaml&lt;/font&gt;&lt;/div&gt;" style="text;html=1;align=left;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="1"> <mxGeometry x="-800" y="370" width="250" height="20" as="geometry" /> </mxCell> <mxCell id="Nch5D1Gedkqk2BCtd5IL-2" value="&lt;div align=&quot;left&quot;&gt;&lt;font style=&quot;font-size: 18px;&quot;&gt;lanelet2_validation_results.yaml&lt;/font&gt;&lt;/div&gt;" style="text;html=1;align=left;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="1"> <mxGeometry x="-190" y="370" width="250" height="20" as="geometry" /> </mxCell> <mxCell id="Nch5D1Gedkqk2BCtd5IL-5" value="&lt;font color=&quot;#9cdcfe&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;requirements:&lt;/font&gt;&lt;font color=&quot;#d69d85&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;&lt;br&gt;&amp;nbsp; - &lt;/font&gt;&lt;font color=&quot;#ccffff&quot;&gt;&lt;/font&gt;&lt;font color=&quot;#9cdcfe&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;id:&lt;/font&gt;&lt;font color=&quot;#d69d85&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt; example-01-01&lt;br&gt;&amp;nbsp;&amp;nbsp;&amp;nbsp; &lt;/font&gt;&lt;font color=&quot;#ccffff&quot;&gt;&lt;/font&gt;&lt;font color=&quot;#9cdcfe&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;validators:&lt;/font&gt;&lt;font color=&quot;#d69d85&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;&lt;br&gt;&amp;nbsp;&amp;nbsp;&amp;nbsp;&amp;nbsp;&amp;nbsp; - &lt;/font&gt;&lt;font color=&quot;#9cdcfe&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;name:&lt;/font&gt;&lt;font color=&quot;#d69d85&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt; mapping.crosswalk.missing_regulatory_elements&lt;br&gt;&amp;nbsp;&amp;nbsp;&amp;nbsp;&amp;nbsp;&amp;nbsp; - &lt;/font&gt;&lt;font color=&quot;#9cdcfe&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;name:&lt;/font&gt;&lt;font color=&quot;#d69d85&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt; mapping.crosswalk.regulatory_element_details&lt;br&gt;&amp;nbsp; - &lt;/font&gt;&lt;font color=&quot;#9cdcfe&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;id:&lt;/font&gt;&lt;font color=&quot;#d69d85&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt; example-01-02&lt;br&gt;&amp;nbsp;&amp;nbsp;&amp;nbsp; &lt;/font&gt;&lt;font color=&quot;#9cdcfe&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;validators:&lt;/font&gt;&lt;font color=&quot;#d69d85&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;&lt;br&gt;&amp;nbsp;&amp;nbsp;&amp;nbsp;&amp;nbsp;&amp;nbsp; - &lt;/font&gt;&lt;font color=&quot;#9cdcfe&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;name:&lt;/font&gt;&lt;font color=&quot;#d69d85&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt; mapping.traffic_light.missing_regulatory_elements&lt;br&gt;&amp;nbsp;&amp;nbsp;&amp;nbsp;&amp;nbsp;&amp;nbsp; - &lt;/font&gt;&lt;font color=&quot;#9cdcfe&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;name:&lt;/font&gt;&lt;font color=&quot;#d69d85&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt; mapping.traffic_light.regulatory_element_details&lt;br&gt;&amp;nbsp; - &lt;/font&gt;&lt;font color=&quot;#9cdcfe&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;id:&lt;/font&gt;&lt;font color=&quot;#d69d85&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt; example-01-03&lt;br&gt;&amp;nbsp;&amp;nbsp;&amp;nbsp; &lt;/font&gt;&lt;font color=&quot;#9cdcfe&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;validators:&lt;/font&gt;&lt;font color=&quot;#d69d85&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;&lt;br&gt;&amp;nbsp;&amp;nbsp;&amp;nbsp;&amp;nbsp;&amp;nbsp; - &lt;/font&gt;&lt;font color=&quot;#9cdcfe&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt;name:&lt;/font&gt;&lt;font color=&quot;#d69d85&quot; face=&quot;SF Mono, Monaco, Menlo, Consolas, Ubuntu Mono, Liberation Mono, DejaVu Sans Mono, Courier New, monospace&quot;&gt; mapping.stop_line.missing_regulatory_elements&lt;/font&gt;" style="text;html=1;align=left;verticalAlign=middle;whiteSpace=wrap;rounded=0;fillColor=#241F31;" vertex="1" parent="1"> <mxGeometry x="-800" y="770" width="540" height="270" as="geometry" /> </mxCell> </root> </mxGraphModel> </diagram> <diagram id="Qp0dXWENBjoYswKNSJSu" name="ページ3"> <mxGraphModel dx="2424" dy="889" grid="1" gridSize="10" guides="1" tooltips="1" connect="1" arrows="1" fold="1" page="1" pageScale="1" pageWidth="827" pageHeight="1169" math="0" shadow="0"> <root> <mxCell id="0" /> <mxCell id="1" parent="0" /> <mxCell id="oA8t_63Oma0dsFNEtsT2-1" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=1;exitY=0.25;exitDx=0;exitDy=0;entryX=0;entryY=0.5;entryDx=0;entryDy=0;" edge="1" parent="1" source="oA8t_63Oma0dsFNEtsT2-2" target="oA8t_63Oma0dsFNEtsT2-24"> <mxGeometry relative="1" as="geometry" /> </mxCell> <mxCell id="oA8t_63Oma0dsFNEtsT2-2" value="" style="rounded=1;whiteSpace=wrap;html=1;strokeColor=#FF0000;strokeWidth=5;" vertex="1" parent="1"> <mxGeometry x="-560" y="130" width="260" height="240" as="geometry" /> </mxCell> <mxCell id="oA8t_63Oma0dsFNEtsT2-4" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=0;exitY=0;exitDx=150;exitDy=35;exitPerimeter=0;entryX=0;entryY=0.25;entryDx=0;entryDy=0;" edge="1" parent="1" source="oA8t_63Oma0dsFNEtsT2-5" target="oA8t_63Oma0dsFNEtsT2-2"> <mxGeometry relative="1" as="geometry" /> </mxCell> <mxCell id="oA8t_63Oma0dsFNEtsT2-5" value="lanelet2_map.osm" style="shape=note;whiteSpace=wrap;html=1;backgroundOutline=1;darkOpacity=0.05;size=15;fillColor=#fff2cc;strokeColor=#8C7738;" vertex="1" parent="1"> <mxGeometry x="-750" y="170" width="150" height="55" as="geometry" /> </mxCell> <mxCell id="oA8t_63Oma0dsFNEtsT2-8" value="lanelet2_validation_results.json" style="shape=note;whiteSpace=wrap;html=1;backgroundOutline=1;darkOpacity=0.05;size=15;fillColor=#CCFFFF;strokeColor=#8C7738;" vertex="1" parent="1"> <mxGeometry x="-260" y="262" width="210" height="53" as="geometry" /> </mxCell> <mxCell id="oA8t_63Oma0dsFNEtsT2-21" value="&lt;font style=&quot;font-size: 18px;&quot;&gt;Input&lt;/font&gt;" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;fontStyle=1" vertex="1" parent="1"> <mxGeometry x="-705" y="130" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="oA8t_63Oma0dsFNEtsT2-22" value="&lt;font style=&quot;font-size: 18px;&quot;&gt;Output&lt;/font&gt;" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;fontStyle=1" vertex="1" parent="1"> <mxGeometry x="-185" y="130" width="60" height="30" as="geometry" /> </mxCell> <mxCell id="oA8t_63Oma0dsFNEtsT2-24" value="&lt;font color=&quot;#b3ff66&quot;&gt;console output&lt;/font&gt;" style="rounded=0;whiteSpace=wrap;html=1;strokeColor=#E6E6E6;fillColor=#241F31;" vertex="1" parent="1"> <mxGeometry x="-260" y="170" width="210" height="53" as="geometry" /> </mxCell> <mxCell id="oA8t_63Oma0dsFNEtsT2-25" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=1;exitY=0.75;exitDx=0;exitDy=0;entryX=0;entryY=0.5;entryDx=0;entryDy=0;entryPerimeter=0;dashed=1;" edge="1" parent="1" source="oA8t_63Oma0dsFNEtsT2-2" target="oA8t_63Oma0dsFNEtsT2-8"> <mxGeometry relative="1" as="geometry" /> </mxCell> <mxCell id="oA8t_63Oma0dsFNEtsT2-26" value="&lt;font style=&quot;font-size: 10px;&quot;&gt;&lt;i&gt;Only if a requirement set input is given&lt;/i&gt;&lt;/font&gt;" style="text;html=1;align=right;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="1"> <mxGeometry x="-275" y="310" width="220" height="25" as="geometry" /> </mxCell> <mxCell id="oA8t_63Oma0dsFNEtsT2-31" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=1;exitY=0.5;exitDx=0;exitDy=0;entryX=0;entryY=0.75;entryDx=0;entryDy=0;" edge="1" parent="1" source="oA8t_63Oma0dsFNEtsT2-30" target="oA8t_63Oma0dsFNEtsT2-2"> <mxGeometry relative="1" as="geometry"> <mxPoint x="-590" y="270" as="targetPoint" /> </mxGeometry> </mxCell> <mxCell id="oA8t_63Oma0dsFNEtsT2-30" value="Validation target ID" style="ellipse;whiteSpace=wrap;html=1;" vertex="1" parent="1"> <mxGeometry x="-740" y="258.5" width="140" height="60" as="geometry" /> </mxCell> <mxCell id="07Wx_InSLLAzkfWwRlwg-1" value="&lt;div align=&quot;center&quot;&gt;autoware_lanelet2_map_validator&lt;/div&gt;&lt;div&gt;&lt;br&gt;&lt;/div&gt;&lt;div&gt;&lt;br&gt;&lt;/div&gt;&lt;div&gt;&lt;br&gt;&lt;/div&gt;&lt;div&gt;&lt;br&gt;&lt;/div&gt;" style="text;whiteSpace=wrap;html=1;align=center;fontStyle=1" vertex="1" parent="1"> <mxGeometry x="-535" y="140" width="210" height="40" as="geometry" /> </mxCell> <mxCell id="07Wx_InSLLAzkfWwRlwg-2" value="Generate scenario &amp;amp;&lt;br&gt;&lt;div&gt;Launch scenario_simulator?&lt;/div&gt;" style="rounded=0;whiteSpace=wrap;html=1;" vertex="1" parent="1"> <mxGeometry x="-530" y="190" width="200" height="40" as="geometry" /> </mxCell> <mxCell id="07Wx_InSLLAzkfWwRlwg-3" value="OR" style="text;whiteSpace=wrap;html=1;align=center;fontStyle=1" vertex="1" parent="1"> <mxGeometry x="-535" y="240" width="210" height="40" as="geometry" /> </mxCell> <mxCell id="07Wx_InSLLAzkfWwRlwg-4" value="Call functions from Planning module?" style="rounded=0;whiteSpace=wrap;html=1;" vertex="1" parent="1"> <mxGeometry x="-535" y="280" width="210" height="40" as="geometry" /> </mxCell> <mxCell id="07Wx_InSLLAzkfWwRlwg-5" value="On " style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="1"> <mxGeometry x="-750" y="80" width="60" height="30" as="geometry" /> </mxCell> </root> </mxGraphModel> </diagram> </mxfile> " > - - - - + - - + + @@ -73,8 +68,8 @@ - - + + @@ -113,8 +108,8 @@ - - + + @@ -135,7 +130,7 @@
- requirement_set.yaml + requirement_set.json
@@ -145,7 +140,7 @@ y="151.5" width="148" height="17" - xlink:href="data:image/png;base64,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" + xlink:href="data:image/png;base64,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" />
@@ -169,7 +164,7 @@
- lanelet2_validation_results.yaml + lanelet2_validation_results.json
@@ -179,7 +174,7 @@ y="152.5" width="208" height="17" - xlink:href="data:image/png;base64,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" + xlink:href="data:image/png;base64,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" />
@@ -719,8 +714,8 @@
- - + + From 8a2a8c26f5087162cf44d03d337e132a0961e5fa Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Thu, 10 Oct 2024 13:58:04 +0900 Subject: [PATCH 29/45] fixed typo Signed-off-by: TaikiYamada4 --- map/autoware_lanelet2_map_validator/src/main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/map/autoware_lanelet2_map_validator/src/main.cpp b/map/autoware_lanelet2_map_validator/src/main.cpp index e92f13eb..8e0fe2ed 100644 --- a/map/autoware_lanelet2_map_validator/src/main.cpp +++ b/map/autoware_lanelet2_map_validator/src/main.cpp @@ -22,7 +22,7 @@ #include #include -// Use nlohmann::json for JSON hndling +// Use nlohmann::json for JSON handling using json = nlohmann::json; // ANSI color codes for console output From 8f159086073c6e90a3b32bf332b0d2b12c8a007a Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Tue, 15 Oct 2024 10:44:58 +0900 Subject: [PATCH 30/45] Renew year numbers Signed-off-by: TaikiYamada4 --- .../crosswalk/missing_regulatory_elements_for_crosswalk.cpp | 2 +- .../crosswalk/regulatory_element_details_for_crosswalks.cpp | 2 +- .../crosswalk/regulatory_element_details_for_crosswalks.hpp | 2 +- .../stop_line/missing_regulatory_elements_for_stop_lines.cpp | 2 +- .../stop_line/missing_regulatory_elements_for_stop_lines.hpp | 2 +- .../missing_regulatory_elements_for_traffic_lights.cpp | 2 +- .../regulatory_element_details_for_traffic_lights.cpp | 2 +- .../regulatory_element_details_for_traffic_lights.hpp | 2 +- .../src/validators/validator_template.cpp | 2 +- .../src/validators/validator_template.hpp | 2 +- 10 files changed, 10 insertions(+), 10 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp index 898dc9d5..f9cb67af 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 Autoware Foundation +// Copyright 2024 Autoware Foundation // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. diff --git a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp index 163f6587..7c305c9e 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 Autoware Foundation +// Copyright 2024 Autoware Foundation // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. diff --git a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp index a352cff6..b0a1bc48 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp +++ b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp @@ -1,4 +1,4 @@ -// Copyright 2023 Autoware Foundation +// Copyright 2024 Autoware Foundation // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. diff --git a/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp b/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp index 2c1b8aca..d23c8ca5 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 Autoware Foundation +// Copyright 2024 Autoware Foundation // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. diff --git a/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp b/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp index 2e97fa55..e1b8682e 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp +++ b/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp @@ -1,4 +1,4 @@ -// Copyright 2023 Autoware Foundation +// Copyright 2024 Autoware Foundation // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. diff --git a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.cpp b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.cpp index aeedc6fe..b0ce0a78 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 Autoware Foundation +// Copyright 2024 Autoware Foundation // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. diff --git a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp index 99d34989..ace36416 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 Autoware Foundation +// Copyright 2024 Autoware Foundation // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. diff --git a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp index d5e64024..321bd35f 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp +++ b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp @@ -1,4 +1,4 @@ -// Copyright 2023 Autoware Foundation +// Copyright 2024 Autoware Foundation // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. diff --git a/map/autoware_lanelet2_map_validator/src/validators/validator_template.cpp b/map/autoware_lanelet2_map_validator/src/validators/validator_template.cpp index c2a921c1..e50644be 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/validator_template.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/validator_template.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 Autoware Foundation +// Copyright 2024 Autoware Foundation // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. diff --git a/map/autoware_lanelet2_map_validator/src/validators/validator_template.hpp b/map/autoware_lanelet2_map_validator/src/validators/validator_template.hpp index dc09c0ff..e541f4e0 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/validator_template.hpp +++ b/map/autoware_lanelet2_map_validator/src/validators/validator_template.hpp @@ -1,4 +1,4 @@ -// Copyright 2023 Autoware Foundation +// Copyright 2024 Autoware Foundation // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. From ef2f5ad63a53eaf7fc1857289ac8377cf489f28e Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Tue, 15 Oct 2024 11:06:44 +0900 Subject: [PATCH 31/45] Fixed dependency Signed-off-by: TaikiYamada4 --- map/autoware_lanelet2_map_validator/package.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/map/autoware_lanelet2_map_validator/package.xml b/map/autoware_lanelet2_map_validator/package.xml index 23fde3b4..b147d461 100644 --- a/map/autoware_lanelet2_map_validator/package.xml +++ b/map/autoware_lanelet2_map_validator/package.xml @@ -18,7 +18,7 @@ lanelet2_routing lanelet2_traffic_rules lanelet2_validation - nlohmann_json + nlohmann-json-dev ament_cmake_ros From b72177d5784eca1468ac12ebbdc6a1fbd800e094 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Fri, 25 Oct 2024 15:41:51 +0900 Subject: [PATCH 32/45] Fixed pointed out issues Signed-off-by: TaikiYamada4 --- map/autoware_lanelet2_map_validator/src/lib/cli.cpp | 8 ++++---- map/autoware_lanelet2_map_validator/src/main.cpp | 8 +++++--- 2 files changed, 9 insertions(+), 7 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/src/lib/cli.cpp b/map/autoware_lanelet2_map_validator/src/lib/cli.cpp index b11472b6..8710d92a 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/cli.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/cli.cpp @@ -29,8 +29,8 @@ MetaConfig parseCommandLine(int argc, const char * argv[]) auto & validation_config = config.command_line_config.validationConfig; 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") + "available"); + desc.add_options()("help,h", "This help message") ("map_file,m", po::value(), "Path to the map to be validated") @@ -60,14 +60,14 @@ MetaConfig parseCommandLine(int argc, const char * argv[]) ("lat", po::value(&validation_config.origin.lat) ->default_value(validation_config.origin.lat), - "latitude coordinate of map origin. This is required for the transverse " + "Latitude coordinate of map origin. This is required for the transverse " "mercator " "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 " + "Longitude coordinate of map origin. This is required for the transverse " "mercator " "and utm projector.") diff --git a/map/autoware_lanelet2_map_validator/src/main.cpp b/map/autoware_lanelet2_map_validator/src/main.cpp index 8e0fe2ed..8ac345f2 100644 --- a/map/autoware_lanelet2_map_validator/src/main.cpp +++ b/map/autoware_lanelet2_map_validator/src/main.cpp @@ -19,6 +19,7 @@ #include +#include #include #include @@ -120,10 +121,11 @@ int process_requirements( } if (!validator_config.output_file_path.empty()) { - std::string file_name = validator_config.output_file_path + "/lanelet2_validation_results.json"; - std::ofstream output_file(file_name); + std::filesystem::path file_directory = validator_config.output_file_path; + std::filesystem::path file_path = file_directory / "lanelet2_validation_results.json"; + std::ofstream output_file(file_path); output_file << std::setw(4) << json_config; - std::cout << "Results are output to " << file_name << std::endl; + std::cout << "Results are output to " << file_path << std::endl; } return (warning_count + error_count == 0) ? 0 : 1; From d16b54b3687330ed4fb9292521e2ce8f543f4879 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Fri, 25 Oct 2024 18:44:22 +0900 Subject: [PATCH 33/45] Improve error handling Refactor code style Signed-off-by: TaikiYamada4 --- .../src/lib/cli.cpp | 63 +++++++------------ .../src/main.cpp | 50 ++++++++------- 2 files changed, 51 insertions(+), 62 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/src/lib/cli.cpp b/map/autoware_lanelet2_map_validator/src/lib/cli.cpp index 8710d92a..a3fff571 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/cli.cpp +++ b/map/autoware_lanelet2_map_validator/src/lib/cli.cpp @@ -30,48 +30,29 @@ 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") + 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")( + "output_directory,o", po::value(), + "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")( + "projector,p", po::value(&config.projector_type)->composing(), + "Projector used for loading lanelet map. Available projectors are: mgrs, utm, " + "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")( + "participants", po::value(&validation_config.participants)->composing(), + "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.")( + "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"); - ("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") - - ("output_directory,o", po::value(), - "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") - - ("projector,p", po::value(&config.projector_type)->composing(), - "Projector used for loading lanelet map. Available projectors are: mgrs, utm, " - "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") - - ("participants", po::value(&validation_config.participants)->composing(), - "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.") - - ("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"); po::variables_map vm; po::positional_options_description pos; pos.add("map_file", 1); diff --git a/map/autoware_lanelet2_map_validator/src/main.cpp b/map/autoware_lanelet2_map_validator/src/main.cpp index 8ac345f2..2e23805a 100644 --- a/map/autoware_lanelet2_map_validator/src/main.cpp +++ b/map/autoware_lanelet2_map_validator/src/main.cpp @@ -35,7 +35,7 @@ using json = nlohmann::json; #define NORMAL_RED "\033[31m" #define FONT_RESET "\033[0m" -int process_requirements( +void process_requirements( json json_config, const lanelet::autoware::validation::MetaConfig & validator_config) { uint64_t warning_count = 0; @@ -121,14 +121,15 @@ int process_requirements( } if (!validator_config.output_file_path.empty()) { + if (!std::filesystem::exists(validator_config.output_file_path)) { + throw std::runtime_error("Output path doesn't exist!"); + } std::filesystem::path file_directory = validator_config.output_file_path; std::filesystem::path file_path = file_directory / "lanelet2_validation_results.json"; std::ofstream output_file(file_path); output_file << std::setw(4) << json_config; std::cout << "Results are output to " << file_path << std::endl; } - - return (warning_count + error_count == 0) ? 0 : 1; } int main(int argc, char * argv[]) @@ -147,32 +148,39 @@ int main(int argc, char * argv[]) auto checks = lanelet::validation::availabeChecks( // cspell:disable-line meta_config.command_line_config.validationConfig.checksFilter); if (checks.empty()) { - std::cout << "No checks found matching '" - << meta_config.command_line_config.validationConfig.checksFilter << "'\n"; + std::cout << "No checks found matching to '" + << meta_config.command_line_config.validationConfig.checksFilter << "'" + << std::endl; } else { - std::cout << "The following checks are available:\n"; + std::cout << "The following checks are available:" << std::endl; for (auto & check : checks) { - std::cout << check << '\n'; + std::cout << check << std::endl; } } return 0; } - // Check whether the map_file is specified - if (meta_config.command_line_config.mapFile.empty()) { - std::cout << "No map file specified" << std::endl; + // Validation start + try { + if (meta_config.command_line_config.mapFile.empty()) { + throw std::runtime_error("No map file specified!"); + } else if (!std::filesystem::exists(meta_config.command_line_config.mapFile)) { + throw std::runtime_error("Map file doesn't exist!"); + } + + if (!meta_config.requirements_file.empty()) { + std::ifstream input_file(meta_config.requirements_file); + json json_config; + input_file >> json_config; + process_requirements(json_config, meta_config); + } else { + auto issues = lanelet::autoware::validation::validateMap(meta_config); + lanelet::validation::printAllIssues(issues); + } + } catch (const std::exception & e) { + std::cout << e.what() << std::endl; return 1; } - // Validation start - if (!meta_config.requirements_file.empty()) { - std::ifstream input_file(meta_config.requirements_file); - json json_config; - input_file >> json_config; - return process_requirements(json_config, meta_config); - } else { - auto issues = lanelet::autoware::validation::validateMap(meta_config); - lanelet::validation::printAllIssues(issues); - return static_cast(!issues.empty()); - } + return 0; } From 8b930271ba07d70319322bfd5e7b0164f6d0e7dc Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Fri, 25 Oct 2024 18:58:07 +0900 Subject: [PATCH 34/45] Avoid clang format Delete unused variables Signed-off-by: TaikiYamada4 --- .../src/lib/cli.cpp | 37 ++++++++++++++----- .../src/lib/validation.cpp | 17 --------- 2 files changed, 27 insertions(+), 27 deletions(-) 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; From c2a437cd2286b4485b86d770a48548541d1149c8 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Mon, 28 Oct 2024 10:40:36 +0900 Subject: [PATCH 35/45] Removed redundant process. Restrict input/output format. Signed-off-by: TaikiYamada4 --- map/autoware_lanelet2_map_validator/src/main.cpp | 8 ++++---- .../missing_regulatory_elements_for_crosswalk.cpp | 11 +---------- 2 files changed, 5 insertions(+), 14 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/src/main.cpp b/map/autoware_lanelet2_map_validator/src/main.cpp index 2e23805a..f15e33c1 100644 --- a/map/autoware_lanelet2_map_validator/src/main.cpp +++ b/map/autoware_lanelet2_map_validator/src/main.cpp @@ -121,8 +121,8 @@ void process_requirements( } if (!validator_config.output_file_path.empty()) { - if (!std::filesystem::exists(validator_config.output_file_path)) { - throw std::runtime_error("Output path doesn't exist!"); + if (!std::filesystem::is_directory(validator_config.output_file_path)) { + throw std::runtime_error("Output path doesn't exist or is not a directory!"); } std::filesystem::path file_directory = validator_config.output_file_path; std::filesystem::path file_path = file_directory / "lanelet2_validation_results.json"; @@ -164,8 +164,8 @@ int main(int argc, char * argv[]) try { if (meta_config.command_line_config.mapFile.empty()) { throw std::runtime_error("No map file specified!"); - } else if (!std::filesystem::exists(meta_config.command_line_config.mapFile)) { - throw std::runtime_error("Map file doesn't exist!"); + } else if (!std::filesystem::is_regular_file(meta_config.command_line_config.mapFile)) { + throw std::runtime_error("Map file doesn't exist or is not a file!"); } if (!meta_config.requirements_file.empty()) { diff --git a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp index f9cb67af..05a0ec60 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp @@ -49,22 +49,13 @@ MissingRegulatoryElementsForCrosswalksValidator::checkMissingRegulatoryElementsF // Get all lanelets whose type is crosswalk std::set cw_ids; - std::set tl_elem_with_cw_; + for (const auto & ll : map.laneletLayer) { const auto & attrs = ll.attributes(); const auto & it = attrs.find(lanelet::AttributeName::Subtype); // Check if this lanelet is crosswalk if (it != attrs.end() && it->second == lanelet::AttributeValueString::Crosswalk) { cw_ids.insert(ll.id()); - - // Check if crosswalk has reg elem of traffic light - for (const auto & elem : ll.regulatoryElements()) { - const auto & attrs = elem->attributes(); - const auto & it = attrs.find(lanelet::AttributeName::Subtype); - if (it != attrs.end() && it->second == lanelet::AttributeValueString::TrafficLight) { - tl_elem_with_cw_.insert(elem->id()); - } - } } } From 6f4770271478cfec9d689894106f7cde586cb1e5 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Mon, 28 Oct 2024 11:58:53 +0900 Subject: [PATCH 36/45] Added approaches to the documents Signed-off-by: TaikiYamada4 --- ...ssing_regulatory_elements_for_crosswalk.md | 7 ++++--- ...gulatory_element_details_for_crosswalks.md | 21 ++++++++++--------- ...sing_regulatory_elements_for_stop_lines.md | 7 ++++--- ..._regulatory_elements_for_traffic_lights.md | 7 ++++--- ...tory_element_details_for_traffic_lights.md | 13 ++++++------ 5 files changed, 30 insertions(+), 25 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/docs/crosswalk/missing_regulatory_elements_for_crosswalk.md b/map/autoware_lanelet2_map_validator/docs/crosswalk/missing_regulatory_elements_for_crosswalk.md index 43ff4327..5506ff5e 100644 --- a/map/autoware_lanelet2_map_validator/docs/crosswalk/missing_regulatory_elements_for_crosswalk.md +++ b/map/autoware_lanelet2_map_validator/docs/crosswalk/missing_regulatory_elements_for_crosswalk.md @@ -7,11 +7,12 @@ mapping.crosswalk.missing_regulatory_elements ## Feature This validator checks whether each `crosswalk` subtype lanelet has a relevant regulatory element. +Required information for a crosswalk is written in the [Autoware documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/map/map-requirements/vector-map-requirements-overview/category_crosswalk/#vm-05-01-crosswalks-across-the-road). The issue specifies the crosswalk "lanelet" as the **primitive**, and the lanelet ID will be specified as the **ID**. -| Message | Severity | Description | -| ------------------------------------------------- | -------- | ------------------------------------------------------------------------------------------- | -| "No regulatory element refers to this crosswalk." | Error | There is a `crosswalk` subtype lanelet that hasn't been referred to any regulatory element. | +| Message | Severity | Description | Approach | +| ------------------------------------------------- | -------- | ------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------- | +| "No regulatory element refers to this crosswalk." | Error | There is a `crosswalk` subtype lanelet that hasn't been referred to any regulatory element. | Create a `crosswalk` subtype regulatory element and refer to the crosswalk lanelet. | ## Related source codes diff --git a/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md b/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md index f275ce75..17d90f1a 100644 --- a/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md +++ b/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md @@ -7,20 +7,21 @@ mapping.crosswalk.regulatory_element_details ## Feature This validator checks whether the details in the `crosswalk` subtype regulatory elements are valid. +Required information for a crosswalk is written in the [Autoware documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/map/map-requirements/vector-map-requirements-overview/category_crosswalk/#vm-05-01-crosswalks-across-the-road). This validator checks seven types of issues. All output issues specify the crosswalk "regulatory element" as the **primitive**, and the lanelet ID will be specified as the **ID**. -| Message | Severity | Description | -| ---------------------------------------------------------------------------------------- | -------- | ---------------------------------------------------------------------------------------------------------------------- | -| "Refers of crosswalk regulatory element must have type of crosswalk." | Error | There is a `crosswalk` subtype regulatory element whose `refers` is not a `crosswalk` subtype lanelet. | -| "ref_line of crosswalk regulatory element must have type of stopline." | Error | There is a `crosswalk` subtype regulatory element whose `ref_line` is not a `stop_line` type linestring. | -| "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon." | Error | There is a `crosswalk` subtype regulatory element whose `crosswalk_polygon` is not a `crosswalk_polygon` type polygon. | -| "Regulatory element of cross walk must have lanelet of crosswalk(refers)." | Error | There is a `crosswalk` subtype regulatory element that has no `refers`es. | -| "Regulatory element of cross walk must have only one lanelet of crosswalk(refers)." | Error | There is a `crosswalk` subtype regulatory element that has multiple `refers`es. | -| "Regulatory element of cross walk does not have stop line(ref_line)." | Info | There is a `crosswalk` subtype regulatory element that has no `ref_line`s | -| "Regulatory element of cross walk is nice to have crosswalk_polygon." | Warning | There is a `crosswalk` subtype regulatory element that has no `crosswalk_polygon`s. | -| "Regulatory element of cross walk must have only one crosswalk_polygon." | Error | There is a `crosswalk` subtype regulatory element that has multiple `crosswalk_polygon`s. | +| Message | Severity | Description | Approach | +| ---------------------------------------------------------------------------------------- | -------- | ---------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| "Refers of crosswalk regulatory element must have type of crosswalk." | Error | There is a `crosswalk` subtype regulatory element whose `refers` is not a `crosswalk` subtype lanelet. | Check that the `refers` is a `crosswalk` subtype lanelet | +| "ref_line of crosswalk regulatory element must have type of stopline." | Error | There is a `crosswalk` subtype regulatory element whose `ref_line` is not a `stop_line` type linestring. | Check that the `ref_line` is a `stop_line` type linestring | +| "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon." | Error | There is a `crosswalk` subtype regulatory element whose `crosswalk_polygon` is not a `crosswalk_polygon` type polygon. | Check that the `crosswalk_polygon` mentioned in the regulatory element refers to a `crosswalk_polygon` type area. | +| "Regulatory element of cross walk must have lanelet of crosswalk(refers)." | Error | There is a `crosswalk` subtype regulatory element that has no `refers`es. | Write `refers` referring to a `crosswalk` subtype lanelet in the regulatory element | +| "Regulatory element of cross walk must have only one lanelet of crosswalk(refers)." | Error | There is a `crosswalk` subtype regulatory element that has multiple `refers`es. | A `crosswalk` subtype regulatory element can have only one `refers`. Remove the `refers` that is not a crosswalk lanelet. | +| "Regulatory element of cross walk does not have stop line(ref_line)." | Info | There is a `crosswalk` subtype regulatory element that has no `ref_line`s | Generally, there should be a stop line for the crosswalk. Be sure that the stop line exists or doesn't. | +| "Regulatory element of cross walk is nice to have crosswalk_polygon." | Warning | There is a `crosswalk` subtype regulatory element that has no `crosswalk_polygon`s. | It is recommended to surround a crosswalk with a `crosswalk_polygon`. Create one and add a `crosswalk_polygon` role member to the regulatory element with the polygon ID. | +| "Regulatory element of cross walk must have only one crosswalk_polygon." | Error | There is a `crosswalk` subtype regulatory element that has multiple `crosswalk_polygon`s. | Only one `crosswalk_polygon` is allowed per polygon. Remove the unnecessary ones. | ## Related source codes diff --git a/map/autoware_lanelet2_map_validator/docs/stop_line/missing_regulatory_elements_for_stop_lines.md b/map/autoware_lanelet2_map_validator/docs/stop_line/missing_regulatory_elements_for_stop_lines.md index 865624a6..84bb85f3 100644 --- a/map/autoware_lanelet2_map_validator/docs/stop_line/missing_regulatory_elements_for_stop_lines.md +++ b/map/autoware_lanelet2_map_validator/docs/stop_line/missing_regulatory_elements_for_stop_lines.md @@ -7,11 +7,12 @@ mapping.stop_line.missing_regulatory_elements ## Feature This validator checks whether each `stop_line` type linestring has a relevant regulatory element. +Required information for a stop line is written in the [Autoware documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/map/map-requirements/vector-map-requirements-overview/category_stop_line/#vm-02-02-stop-sign). The issue specifies the stop_line "linestring" as the **primitive**, and the lanelet ID will be specified as the **ID**. -| Message | Severity | Description | -| ------------------------------------------------- | -------- | ------------------------------------------------------------------------------------------- | -| "No regulatory element refers to this stop line." | Error | There is a `stop_line` type linestring that hasn't been referred to any regulatory element. | +| Message | Severity | Description | Approach | +| ------------------------------------------------- | -------- | ------------------------------------------------------------------------------------------- | ---------------------------------------------------------- | +| "No regulatory element refers to this stop line." | Error | There is a `stop_line` type linestring that hasn't been referred to any regulatory element. | Create a regulatory element that refers to this stop line. | ## Related source codes diff --git a/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md b/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md index 95b576c8..6ceb0914 100644 --- a/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md +++ b/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md @@ -7,11 +7,12 @@ mapping.traffic_light.missing_regulatory_elements ## Feature This validator checks whether each `traffic_light` type linestring has a relevant regulatory element. +Required information for traffic lights is written in the [Autoware documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/map/map-requirements/vector-map-requirements-overview/category_traffic_light/#vm-04-01-traffic-light-basics). The output issue specifies the traffic_light "linestring" as the **primitive**, and the linestring ID will be specified as the **ID**. -| Message | Severity | Description | -| ----------------------------------------------------- | -------- | ----------------------------------------------------------------------------------------------- | -| "No regulatory element refers to this traffic light." | Error | There is a `traffic_light` type linestring that hasn't been referred to any regulatory element. | +| Message | Severity | Description | Approach | +| ----------------------------------------------------- | -------- | ----------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------- | +| "No regulatory element refers to this traffic light." | Error | There is a `traffic_light` type linestring that hasn't been referred to any regulatory element. | Create a `traffic_light` subtype regualtroy element that refers to this linestring | ## Related source codes diff --git a/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md b/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md index ed0dedb4..9f560015 100644 --- a/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md +++ b/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md @@ -7,16 +7,17 @@ mapping.traffic_light.regulatory_element_details ## Feature This validator checks whether the details in the `traffic_light` subtype regulatory elements are valid. +Required information for traffic lights is written in the [Autoware documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/map/map-requirements/vector-map-requirements-overview/category_traffic_light/#vm-04-01-traffic-light-basics). This validator checks four types of issues. All output issues specify the traffic_light "regulatory element" as the **primitive**, and the linestring ID will be specified as the **ID**. -| Message | Severity | Description | -| ----------------------------------------------------------------------------- | -------- | -------------------------------------------------------------------------------------------------------------- | -| "Refers of traffic light regulatory element must have type of traffic_light." | Error | There is a `traffic_light` subtype regulatory element whose `refers` is not a `traffic_light` type linestring. | -| "ref_line of traffic light regulatory element must have type of stop_line." | Error | There is a `traffic_light` subtype regulatory element whose `ref_line` is not a `stop_line` type linestring. | -| "Regulatory element of traffic light must have a traffic light(refers)." | Error | There is a `traffic_light` subtype regulatory element that has no `refers`es. | -| "Regulatory element of traffic light must have a stop line(ref_line)." | Error | There is a `traffic_light` subtype regulatory element that has no `ref_line`s | +| Message | Severity | Description | Approach | +| ----------------------------------------------------------------------------- | -------- | -------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------- | +| "Refers of traffic light regulatory element must have type of traffic_light." | Error | There is a `traffic_light` subtype regulatory element whose `refers` is not a `traffic_light` type linestring. | Check that the `refers` in the regulatory element is a `traffic_light` type linestring. | +| "ref_line of traffic light regulatory element must have type of stop_line." | Error | There is a `traffic_light` subtype regulatory element whose `ref_line` is not a `stop_line` type linestring. | Check that the `ref_line` in the regulatory element is a `stop_line` type linestring | +| "Regulatory element of traffic light must have a traffic light(refers)." | Error | There is a `traffic_light` subtype regulatory element that has no `refers`es. | Add `refers` to the regulatory element that refers to the id of the traffic light linestring. | +| "Regulatory element of traffic light must have a stop line(ref_line)." | Error | There is a `traffic_light` subtype regulatory element that has no `ref_line`s | Add `ref_line` to the regulatory element that refers to the id of the stop line linestring. | ## Related source codes From c114991e283bce0202e42826f908414353691770 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Mon, 28 Oct 2024 12:41:59 +0900 Subject: [PATCH 37/45] Fixed typo Signed-off-by: TaikiYamada4 --- .../missing_regulatory_elements_for_traffic_lights.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md b/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md index 6ceb0914..6fb967e7 100644 --- a/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md +++ b/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md @@ -12,7 +12,7 @@ The output issue specifies the traffic_light "linestring" as the **primitive**, | Message | Severity | Description | Approach | | ----------------------------------------------------- | -------- | ----------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------- | -| "No regulatory element refers to this traffic light." | Error | There is a `traffic_light` type linestring that hasn't been referred to any regulatory element. | Create a `traffic_light` subtype regualtroy element that refers to this linestring | +| "No regulatory element refers to this traffic light." | Error | There is a `traffic_light` type linestring that hasn't been referred to any regulatory element. | Create a `traffic_light` subtype regulatory element that refers to this linestring | ## Related source codes From fe9d19a5129137884b4027aab78909bc825a924c Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Mon, 28 Oct 2024 16:01:46 +0900 Subject: [PATCH 38/45] Removed catch and improve io error handling Signed-off-by: TaikiYamada4 --- .../src/main.cpp | 34 +++++++++---------- 1 file changed, 16 insertions(+), 18 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/src/main.cpp b/map/autoware_lanelet2_map_validator/src/main.cpp index f15e33c1..0579dadf 100644 --- a/map/autoware_lanelet2_map_validator/src/main.cpp +++ b/map/autoware_lanelet2_map_validator/src/main.cpp @@ -122,7 +122,7 @@ void process_requirements( if (!validator_config.output_file_path.empty()) { if (!std::filesystem::is_directory(validator_config.output_file_path)) { - throw std::runtime_error("Output path doesn't exist or is not a directory!"); + throw std::invalid_argument("Output path doesn't exist or is not a directory!"); } std::filesystem::path file_directory = validator_config.output_file_path; std::filesystem::path file_path = file_directory / "lanelet2_validation_results.json"; @@ -161,25 +161,23 @@ int main(int argc, char * argv[]) } // Validation start - try { - if (meta_config.command_line_config.mapFile.empty()) { - throw std::runtime_error("No map file specified!"); - } else if (!std::filesystem::is_regular_file(meta_config.command_line_config.mapFile)) { - throw std::runtime_error("Map file doesn't exist or is not a file!"); - } + if (meta_config.command_line_config.mapFile.empty()) { + throw std::invalid_argument("No map file specified!"); + } else if (!std::filesystem::is_regular_file(meta_config.command_line_config.mapFile)) { + throw std::invalid_argument("Map file doesn't exist or is not a file!"); + } - if (!meta_config.requirements_file.empty()) { - std::ifstream input_file(meta_config.requirements_file); - json json_config; - input_file >> json_config; - process_requirements(json_config, meta_config); - } else { - auto issues = lanelet::autoware::validation::validateMap(meta_config); - lanelet::validation::printAllIssues(issues); + if (!meta_config.requirements_file.empty()) { + if (!std::filesystem::is_regular_file(meta_config.requirements_file)) { + throw std::invalid_argument("Input file doesn't exist or is not a file!"); } - } catch (const std::exception & e) { - std::cout << e.what() << std::endl; - return 1; + std::ifstream input_file(meta_config.requirements_file); + json json_config; + input_file >> json_config; + process_requirements(json_config, meta_config); + } else { + auto issues = lanelet::autoware::validation::validateMap(meta_config); + lanelet::validation::printAllIssues(issues); } return 0; From 98b4ee60b2d7bd9c99274a1b0761bf7935ed46f2 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Mon, 28 Oct 2024 17:40:26 +0900 Subject: [PATCH 39/45] Fixed grammatical error. Fixed explanation of issues Signed-off-by: TaikiYamada4 --- map/autoware_lanelet2_map_validator/README.md | 6 ++-- ...ssing_regulatory_elements_for_crosswalk.md | 3 +- ...gulatory_element_details_for_crosswalks.md | 28 +++++++++---------- ...sing_regulatory_elements_for_stop_lines.md | 3 +- ..._regulatory_elements_for_traffic_lights.md | 3 +- ...tory_element_details_for_traffic_lights.md | 16 +++++------ ...ulatory_element_details_for_crosswalks.cpp | 10 +++---- .../src/test_regulatory_element_details.cpp | 8 +++--- 8 files changed, 40 insertions(+), 37 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/README.md b/map/autoware_lanelet2_map_validator/README.md index 3a85e9cf..6ff1c645 100644 --- a/map/autoware_lanelet2_map_validator/README.md +++ b/map/autoware_lanelet2_map_validator/README.md @@ -215,7 +215,7 @@ When the `input_requirements` is thrown to `autoware_lanelet2_map_validator`, it - `lanelet2_validation_results.json` inherits the JSON file of `input_requirements` and add results to it. - So non-required fields (line `version`) remains in the output. - `autoware_lanelet2_map_validator` adds a boolean `passed` field to each requirement. If all validators of the requirement have been passed, the `passed` field of the requirement will be `true` (`false` if not). -- The `passed` field is also given to each validator. If the validator found any issues the `passed` field will turn to be `false` (`true` if not), and adds an `issues` field which is a list of issues found. Each issues contains information of `severity`, `primitive`, `id`, and `message`. +- The `passed` field is also given to each validator. If the validator found any issues the `passed` field will turn to be `false` (`true` if not), and adds an `issues` field which is a list of issues found. Each issue contains information of `severity`, `primitive`, `id`, and `message`. ### Available command options @@ -235,7 +235,7 @@ When the `input_requirements` is thrown to `autoware_lanelet2_map_validator`, it ### Available validators -Since there will be hundreds of validators in the future, the documents for each validators should categorized in the docs file. +Since there will be hundreds of validators in the future, the documents for each validator should categorized in the docs file. The directory structure should be the same to that of the `src/lib/validators` directory. #### Stop Line @@ -255,7 +255,7 @@ The directory structure should be the same to that of the `src/lib/validators` d ## Relationship between requirements and validators This is a table describing the correspondence between the validators that each requirement consists of. -The Validators column will be blank if it hasn't be implemented. +The "Validators" column will be blank if it hasn't be implemented. | ID | Requirements | Validators | | -------- | ------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | diff --git a/map/autoware_lanelet2_map_validator/docs/crosswalk/missing_regulatory_elements_for_crosswalk.md b/map/autoware_lanelet2_map_validator/docs/crosswalk/missing_regulatory_elements_for_crosswalk.md index 5506ff5e..c96ec6d4 100644 --- a/map/autoware_lanelet2_map_validator/docs/crosswalk/missing_regulatory_elements_for_crosswalk.md +++ b/map/autoware_lanelet2_map_validator/docs/crosswalk/missing_regulatory_elements_for_crosswalk.md @@ -8,7 +8,8 @@ mapping.crosswalk.missing_regulatory_elements This validator checks whether each `crosswalk` subtype lanelet has a relevant regulatory element. Required information for a crosswalk is written in the [Autoware documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/map/map-requirements/vector-map-requirements-overview/category_crosswalk/#vm-05-01-crosswalks-across-the-road). -The issue specifies the crosswalk "lanelet" as the **primitive**, and the lanelet ID will be specified as the **ID**. + +The output issue marks "lanelet" as the **primitive**, and the lanelet ID is written together as **ID**. | Message | Severity | Description | Approach | | ------------------------------------------------- | -------- | ------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------- | diff --git a/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md b/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md index 17d90f1a..62d003e7 100644 --- a/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md +++ b/map/autoware_lanelet2_map_validator/docs/crosswalk/regulatory_element_details_for_crosswalks.md @@ -8,20 +8,20 @@ mapping.crosswalk.regulatory_element_details This validator checks whether the details in the `crosswalk` subtype regulatory elements are valid. Required information for a crosswalk is written in the [Autoware documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/map/map-requirements/vector-map-requirements-overview/category_crosswalk/#vm-05-01-crosswalks-across-the-road). -This validator checks seven types of issues. - -All output issues specify the crosswalk "regulatory element" as the **primitive**, and the lanelet ID will be specified as the **ID**. - -| Message | Severity | Description | Approach | -| ---------------------------------------------------------------------------------------- | -------- | ---------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| "Refers of crosswalk regulatory element must have type of crosswalk." | Error | There is a `crosswalk` subtype regulatory element whose `refers` is not a `crosswalk` subtype lanelet. | Check that the `refers` is a `crosswalk` subtype lanelet | -| "ref_line of crosswalk regulatory element must have type of stopline." | Error | There is a `crosswalk` subtype regulatory element whose `ref_line` is not a `stop_line` type linestring. | Check that the `ref_line` is a `stop_line` type linestring | -| "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon." | Error | There is a `crosswalk` subtype regulatory element whose `crosswalk_polygon` is not a `crosswalk_polygon` type polygon. | Check that the `crosswalk_polygon` mentioned in the regulatory element refers to a `crosswalk_polygon` type area. | -| "Regulatory element of cross walk must have lanelet of crosswalk(refers)." | Error | There is a `crosswalk` subtype regulatory element that has no `refers`es. | Write `refers` referring to a `crosswalk` subtype lanelet in the regulatory element | -| "Regulatory element of cross walk must have only one lanelet of crosswalk(refers)." | Error | There is a `crosswalk` subtype regulatory element that has multiple `refers`es. | A `crosswalk` subtype regulatory element can have only one `refers`. Remove the `refers` that is not a crosswalk lanelet. | -| "Regulatory element of cross walk does not have stop line(ref_line)." | Info | There is a `crosswalk` subtype regulatory element that has no `ref_line`s | Generally, there should be a stop line for the crosswalk. Be sure that the stop line exists or doesn't. | -| "Regulatory element of cross walk is nice to have crosswalk_polygon." | Warning | There is a `crosswalk` subtype regulatory element that has no `crosswalk_polygon`s. | It is recommended to surround a crosswalk with a `crosswalk_polygon`. Create one and add a `crosswalk_polygon` role member to the regulatory element with the polygon ID. | -| "Regulatory element of cross walk must have only one crosswalk_polygon." | Error | There is a `crosswalk` subtype regulatory element that has multiple `crosswalk_polygon`s. | Only one `crosswalk_polygon` is allowed per polygon. Remove the unnecessary ones. | +This validator checks eight types of issues. + +The output issue marks "lanelet", "linestring" or "regulatory_element" as the **primitive**, and the regulatory element ID is written together as **ID**. + +| Message | Severity | Primitive | Description | Approach | +| ---------------------------------------------------------------------------------------- | -------- | ------------------ | ---------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| "Refers of crosswalk regulatory element must have type of crosswalk." | Error | lanelet | There is a `crosswalk` subtype regulatory element whose `refers` is not a `crosswalk` subtype lanelet. | Check that the `refers` is a `crosswalk` subtype lanelet | +| "ref_line of crosswalk regulatory element must have type of stopline." | Error | linestring | There is a `crosswalk` subtype regulatory element whose `ref_line` is not a `stop_line` type linestring. | Check that the `ref_line` is a `stop_line` type linestring | +| "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon." | Error | polygon | There is a `crosswalk` subtype regulatory element whose `crosswalk_polygon` is not a `crosswalk_polygon` type polygon. | Check that the `crosswalk_polygon` mentioned in the regulatory element refers to a `crosswalk_polygon` type area. | +| "Regulatory element of crosswalk must have lanelet of crosswalk(refers)." | Error | regulatory element | There is a `crosswalk` subtype regulatory element that has no `refers`es. | Write `refers` referring to a `crosswalk` subtype lanelet in the regulatory element | +| "Regulatory element of crosswalk must have only one lanelet of crosswalk(refers)." | Error | regulatory element | There is a `crosswalk` subtype regulatory element that has multiple `refers`es. | A `crosswalk` subtype regulatory element can have only one `refers`. Remove the `refers` that is not a crosswalk lanelet. | +| "Regulatory element of crosswalk does not have stop line(ref_line)." | Info | regulatory element | There is a `crosswalk` subtype regulatory element that has no `ref_line`s | Generally, there should be a stop line for the crosswalk. Be sure that the stop line exists or doesn't. | +| "Regulatory element of crosswalk is nice to have crosswalk_polygon." | Warning | regulatory element | There is a `crosswalk` subtype regulatory element that has no `crosswalk_polygon`s. | It is recommended to surround a crosswalk with a `crosswalk_polygon`. Create one and add a `crosswalk_polygon` role member to the regulatory element with the polygon ID. | +| "Regulatory element of crosswalk must have only one crosswalk_polygon." | Error | regulatory element | There is a `crosswalk` subtype regulatory element that has multiple `crosswalk_polygon`s. | Only one `crosswalk_polygon` is allowed per polygon. Remove the unnecessary ones. | ## Related source codes diff --git a/map/autoware_lanelet2_map_validator/docs/stop_line/missing_regulatory_elements_for_stop_lines.md b/map/autoware_lanelet2_map_validator/docs/stop_line/missing_regulatory_elements_for_stop_lines.md index 84bb85f3..fb286208 100644 --- a/map/autoware_lanelet2_map_validator/docs/stop_line/missing_regulatory_elements_for_stop_lines.md +++ b/map/autoware_lanelet2_map_validator/docs/stop_line/missing_regulatory_elements_for_stop_lines.md @@ -8,7 +8,8 @@ mapping.stop_line.missing_regulatory_elements This validator checks whether each `stop_line` type linestring has a relevant regulatory element. Required information for a stop line is written in the [Autoware documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/map/map-requirements/vector-map-requirements-overview/category_stop_line/#vm-02-02-stop-sign). -The issue specifies the stop_line "linestring" as the **primitive**, and the lanelet ID will be specified as the **ID**. + +The output issue marks "linestring" as the **primitive**, and the linestring ID is written together as **ID**. | Message | Severity | Description | Approach | | ------------------------------------------------- | -------- | ------------------------------------------------------------------------------------------- | ---------------------------------------------------------- | diff --git a/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md b/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md index 6fb967e7..4bcb311d 100644 --- a/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md +++ b/map/autoware_lanelet2_map_validator/docs/traffic_light/missing_regulatory_elements_for_traffic_lights.md @@ -8,7 +8,8 @@ mapping.traffic_light.missing_regulatory_elements This validator checks whether each `traffic_light` type linestring has a relevant regulatory element. Required information for traffic lights is written in the [Autoware documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/map/map-requirements/vector-map-requirements-overview/category_traffic_light/#vm-04-01-traffic-light-basics). -The output issue specifies the traffic_light "linestring" as the **primitive**, and the linestring ID will be specified as the **ID**. + +The output issue marks "linestring" as the **primitive**, and the linestring ID is written together as **ID**. | Message | Severity | Description | Approach | | ----------------------------------------------------- | -------- | ----------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------- | diff --git a/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md b/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md index 9f560015..29a585d4 100644 --- a/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md +++ b/map/autoware_lanelet2_map_validator/docs/traffic_light/regulatory_element_details_for_traffic_lights.md @@ -10,14 +10,14 @@ This validator checks whether the details in the `traffic_light` subtype regulat Required information for traffic lights is written in the [Autoware documentation](https://autowarefoundation.github.io/autoware-documentation/main/design/autoware-architecture/map/map-requirements/vector-map-requirements-overview/category_traffic_light/#vm-04-01-traffic-light-basics). This validator checks four types of issues. -All output issues specify the traffic_light "regulatory element" as the **primitive**, and the linestring ID will be specified as the **ID**. - -| Message | Severity | Description | Approach | -| ----------------------------------------------------------------------------- | -------- | -------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------- | -| "Refers of traffic light regulatory element must have type of traffic_light." | Error | There is a `traffic_light` subtype regulatory element whose `refers` is not a `traffic_light` type linestring. | Check that the `refers` in the regulatory element is a `traffic_light` type linestring. | -| "ref_line of traffic light regulatory element must have type of stop_line." | Error | There is a `traffic_light` subtype regulatory element whose `ref_line` is not a `stop_line` type linestring. | Check that the `ref_line` in the regulatory element is a `stop_line` type linestring | -| "Regulatory element of traffic light must have a traffic light(refers)." | Error | There is a `traffic_light` subtype regulatory element that has no `refers`es. | Add `refers` to the regulatory element that refers to the id of the traffic light linestring. | -| "Regulatory element of traffic light must have a stop line(ref_line)." | Error | There is a `traffic_light` subtype regulatory element that has no `ref_line`s | Add `ref_line` to the regulatory element that refers to the id of the stop line linestring. | +The output issue marks "linestring" or "regulatory element" as the **primitive**, and the lanelet ID is written together as **ID**. + +| Message | Severity | Primitive | Description | Approach | +| ----------------------------------------------------------------------------- | -------- | ------------------ | -------------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------- | +| "Refers of traffic light regulatory element must have type of traffic_light." | Error | linestring | There is a `traffic_light` subtype regulatory element whose `refers` is not a `traffic_light` type linestring. | Check that the `refers` in the regulatory element is a `traffic_light` type linestring. | +| "ref_line of traffic light regulatory element must have type of stop_line." | Error | linestring | There is a `traffic_light` subtype regulatory element whose `ref_line` is not a `stop_line` type linestring. | Check that the `ref_line` in the regulatory element is a `stop_line` type linestring | +| "Regulatory element of traffic light must have a traffic light(refers)." | Error | regulatory element | There is a `traffic_light` subtype regulatory element that has no `refers`es. | Add `refers` to the regulatory element that refers to the id of the traffic light linestring. | +| "Regulatory element of traffic light must have a stop line(ref_line)." | Error | regulatory element | There is a `traffic_light` subtype regulatory element that has no `ref_line`s | Add `ref_line` to the regulatory element that refers to the id of the stop line linestring. | ## Related source codes diff --git a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp index 7c305c9e..1502c2a5 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp @@ -96,30 +96,30 @@ RegulatoryElementsDetailsForCrosswalksValidator::checkRegulatoryElementOfCrosswa if (crosswalk_polygons.empty()) { issues.emplace_back( lanelet::validation::Severity::Warning, lanelet::validation::Primitive::RegulatoryElement, - elem->id(), "Regulatory element of cross walk is nice to have crosswalk_polygon."); + elem->id(), "Regulatory element of crosswalk is nice to have crosswalk_polygon."); } else if (crosswalk_polygons.size() > 1) { // Report error if regulatory element has two or // more crosswalk polygon issues.emplace_back( lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, - elem->id(), "Regulatory element of cross walk must have only one crosswalk_polygon."); + elem->id(), "Regulatory element of crosswalk must have only one crosswalk_polygon."); } // Report Info if regulatory element does not have stop line if (ref_lines.empty()) { issues.emplace_back( lanelet::validation::Severity::Info, lanelet::validation::Primitive::RegulatoryElement, - elem->id(), "Regulatory element of cross walk does not have stop line(ref_line)."); + elem->id(), "Regulatory element of crosswalk does not have stop line(ref_line)."); } // Report error if regulatory element does not have lanelet of crosswalk if (refers.empty()) { issues.emplace_back( lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, - elem->id(), "Regulatory element of cross walk must have lanelet of crosswalk(refers)."); + elem->id(), "Regulatory element of crosswalk must have lanelet of crosswalk(refers)."); } else if (refers.size() > 1) { // Report error if regulatory element has two or more lanelet // of crosswalk issues.emplace_back( lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, elem->id(), - "Regulatory element of cross walk must have only one lanelet of crosswalk(refers)."); + "Regulatory element of crosswalk must have only one lanelet of crosswalk(refers)."); } } return issues; diff --git a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp index 43deee94..83a40a6b 100644 --- a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp +++ b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp @@ -257,7 +257,7 @@ TEST_F(TestSuite, RegulatoryElementOfCrosswalkWithoutPolygon) // NOLINT for gte LineString3d(getId(), {Point3d(getId(), 3.0, 1.0, 0.1), Point3d(getId(), 3.0, 2.0, 0.1)}), cw_attr); - // Crosswalk regulatory element without cross walk polygon. It refers to the polygon without cross + // Crosswalk regulatory element without crosswalk polygon. It refers to the polygon without cross // walk polygon attribute. RegulatoryElementPtr reg_elem = Crosswalk::make( 99999, cw_re_attr, cw_no_poly, Polygon3d(99998), @@ -274,7 +274,7 @@ TEST_F(TestSuite, RegulatoryElementOfCrosswalkWithoutPolygon) // NOLINT for gte static constexpr const char * expected_message1 = "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon."; static constexpr const char * expected_message2 = - "Regulatory element of cross walk is nice to have crosswalk_polygon."; + "Regulatory element of crosswalk is nice to have crosswalk_polygon."; EXPECT_EQ(expected_num_issues, issues.size()); for (const auto & issue : issues) { if (issue.id == 99998) { @@ -314,7 +314,7 @@ TEST_F(TestSuite, RegulatoryElementOfCrosswalkWithoutStopline) // NOLINT for gt uint8_t expected_num_issues = 1; static constexpr const char * expected_message = - "Regulatory element of cross walk does not have stop line(ref_line)."; + "Regulatory element of crosswalk does not have stop line(ref_line)."; EXPECT_EQ(expected_num_issues, issues.size()); for (const auto & issue : issues) { EXPECT_EQ(expected_message, issue.message); @@ -350,7 +350,7 @@ TEST_F(TestSuite, RegulatoryElementOfCrosswalkWithoutCrosswalk) // NOLINT for g static constexpr const char * expected_message1 = "Refers of crosswalk regulatory element must have type of crosswalk."; static constexpr const char * expected_message2 = - "Regulatory element of cross walk must have lanelet of crosswalk(refers)."; + "Regulatory element of crosswalk must have lanelet of crosswalk(refers)."; EXPECT_EQ(expected_num_issues, issues.size()); for (const auto & issue : issues) { if (issue.id == 99998) { From b405d14d30dfb317d51ebfb182bd6ac46ec4d7f4 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Mon, 28 Oct 2024 18:00:48 +0900 Subject: [PATCH 40/45] Added stop_line validator to the table in the main README.md Signed-off-by: TaikiYamada4 --- map/autoware_lanelet2_map_validator/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/map/autoware_lanelet2_map_validator/README.md b/map/autoware_lanelet2_map_validator/README.md index 6ff1c645..83134dee 100644 --- a/map/autoware_lanelet2_map_validator/README.md +++ b/map/autoware_lanelet2_map_validator/README.md @@ -279,7 +279,7 @@ The "Validators" column will be blank if it hasn't be implemented. | vm-01-18 | Side strip Linestring sharing | | | vm-01-19 | Walkway | | | vm-02-01 | Stop line alignment | | -| vm-02-02 | Stop sign | | +| vm-02-02 | Stop sign | [mapping.stop_line.missing_regulatory_elements](./docs/stop_line/missing_regulatory_elements_for_stop_lines.md) | | vm-03-01 | Intersection criteria | | | vm-03-02 | Lanelet's turn direction and virtual | | | vm-03-03 | Lanelet width in the intersection | | From 4570bbf190a19313649988ec911f0ae3d899bed3 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Mon, 28 Oct 2024 18:23:39 +0900 Subject: [PATCH 41/45] Renamed lib to common. Refined CMakeLists.txt Signed-off-by: TaikiYamada4 --- map/autoware_lanelet2_map_validator/CMakeLists.txt | 5 ++++- map/autoware_lanelet2_map_validator/README.md | 2 +- .../src/{lib => common}/cli.cpp | 2 +- .../src/{lib => common}/cli.hpp | 6 +++--- .../src/{lib => common}/utils.hpp | 6 +++--- .../src/{lib => common}/validation.cpp | 2 +- .../src/{lib => common}/validation.hpp | 10 +++++----- map/autoware_lanelet2_map_validator/src/main.cpp | 6 +++--- .../missing_regulatory_elements_for_crosswalk.cpp | 2 +- .../regulatory_element_details_for_crosswalks.cpp | 2 +- .../missing_regulatory_elements_for_stop_lines.cpp | 2 +- .../missing_regulatory_elements_for_traffic_lights.cpp | 2 +- .../regulatory_element_details_for_traffic_lights.cpp | 2 +- 13 files changed, 26 insertions(+), 23 deletions(-) rename map/autoware_lanelet2_map_validator/src/{lib => common}/cli.cpp (99%) rename map/autoware_lanelet2_map_validator/src/{lib => common}/cli.hpp (93%) rename map/autoware_lanelet2_map_validator/src/{lib => common}/utils.hpp (96%) rename map/autoware_lanelet2_map_validator/src/{lib => common}/validation.cpp (98%) rename map/autoware_lanelet2_map_validator/src/{lib => common}/validation.hpp (89%) diff --git a/map/autoware_lanelet2_map_validator/CMakeLists.txt b/map/autoware_lanelet2_map_validator/CMakeLists.txt index f80d4b7d..a8065ed1 100644 --- a/map/autoware_lanelet2_map_validator/CMakeLists.txt +++ b/map/autoware_lanelet2_map_validator/CMakeLists.txt @@ -11,7 +11,10 @@ include_directories( src ) -file(GLOB_RECURSE autoware_lanelet2_map_validator_lib_src src/*.cpp) +file(GLOB_RECURSE autoware_lanelet2_map_validator_lib_src + src/common/*.cpp + src/validators/*.cpp +) ament_auto_add_library(autoware_lanelet2_map_validator_lib SHARED ${autoware_lanelet2_map_validator_lib_src} ) diff --git a/map/autoware_lanelet2_map_validator/README.md b/map/autoware_lanelet2_map_validator/README.md index 83134dee..f20eab92 100644 --- a/map/autoware_lanelet2_map_validator/README.md +++ b/map/autoware_lanelet2_map_validator/README.md @@ -236,7 +236,7 @@ When the `input_requirements` is thrown to `autoware_lanelet2_map_validator`, it ### Available validators Since there will be hundreds of validators in the future, the documents for each validator should categorized in the docs file. -The directory structure should be the same to that of the `src/lib/validators` directory. +The directory structure should be the same to that of the `src/validators` directory. #### Stop Line diff --git a/map/autoware_lanelet2_map_validator/src/lib/cli.cpp b/map/autoware_lanelet2_map_validator/src/common/cli.cpp similarity index 99% rename from map/autoware_lanelet2_map_validator/src/lib/cli.cpp rename to map/autoware_lanelet2_map_validator/src/common/cli.cpp index 00bf7cc9..ee5300d4 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/cli.cpp +++ b/map/autoware_lanelet2_map_validator/src/common/cli.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "lib/cli.hpp" +#include "common/cli.hpp" namespace po = boost::program_options; diff --git a/map/autoware_lanelet2_map_validator/src/lib/cli.hpp b/map/autoware_lanelet2_map_validator/src/common/cli.hpp similarity index 93% rename from map/autoware_lanelet2_map_validator/src/lib/cli.hpp rename to map/autoware_lanelet2_map_validator/src/common/cli.hpp index ff94469f..d3552604 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/cli.hpp +++ b/map/autoware_lanelet2_map_validator/src/common/cli.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef LIB__CLI_HPP_ -#define LIB__CLI_HPP_ +#ifndef COMMON__CLI_HPP_ +#define COMMON__CLI_HPP_ #include @@ -42,4 +42,4 @@ MetaConfig parseCommandLine(int argc, const char * argv[]); } // namespace autoware } // namespace lanelet -#endif // LIB__CLI_HPP_ +#endif // COMMON__CLI_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/lib/utils.hpp b/map/autoware_lanelet2_map_validator/src/common/utils.hpp similarity index 96% rename from map/autoware_lanelet2_map_validator/src/lib/utils.hpp rename to map/autoware_lanelet2_map_validator/src/common/utils.hpp index 57a474f1..82ab18c5 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/utils.hpp +++ b/map/autoware_lanelet2_map_validator/src/common/utils.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef LIB__UTILS_HPP_ -#define LIB__UTILS_HPP_ +#ifndef COMMON__UTILS_HPP_ +#define COMMON__UTILS_HPP_ #include #include @@ -82,4 +82,4 @@ void checkPrimitivesType( } // namespace autoware } // namespace lanelet -#endif // LIB__UTILS_HPP_ +#endif // COMMON__UTILS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/lib/validation.cpp b/map/autoware_lanelet2_map_validator/src/common/validation.cpp similarity index 98% rename from map/autoware_lanelet2_map_validator/src/lib/validation.cpp rename to map/autoware_lanelet2_map_validator/src/common/validation.cpp index 9a8d0cae..b112dbdd 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validation.cpp +++ b/map/autoware_lanelet2_map_validator/src/common/validation.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "lib/validation.hpp" +#include "common/validation.hpp" #include #include diff --git a/map/autoware_lanelet2_map_validator/src/lib/validation.hpp b/map/autoware_lanelet2_map_validator/src/common/validation.hpp similarity index 89% rename from map/autoware_lanelet2_map_validator/src/lib/validation.hpp rename to map/autoware_lanelet2_map_validator/src/common/validation.hpp index 984b26d8..67e034e6 100644 --- a/map/autoware_lanelet2_map_validator/src/lib/validation.hpp +++ b/map/autoware_lanelet2_map_validator/src/common/validation.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef LIB__VALIDATION_HPP_ -#define LIB__VALIDATION_HPP_ +#ifndef COMMON__VALIDATION_HPP_ +#define COMMON__VALIDATION_HPP_ -#include "lib/cli.hpp" -#include "lib/utils.hpp" +#include "common/cli.hpp" +#include "common/utils.hpp" #include #include @@ -49,4 +49,4 @@ std::vector validateMap(const MetaConfig & } // namespace autoware } // namespace lanelet -#endif // LIB__VALIDATION_HPP_ +#endif // COMMON__VALIDATION_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/main.cpp b/map/autoware_lanelet2_map_validator/src/main.cpp index 0579dadf..07804c0f 100644 --- a/map/autoware_lanelet2_map_validator/src/main.cpp +++ b/map/autoware_lanelet2_map_validator/src/main.cpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include "common/cli.hpp" +#include "common/utils.hpp" +#include "common/validation.hpp" #include "lanelet2_validation/Validation.h" -#include "lib/cli.hpp" -#include "lib/utils.hpp" -#include "lib/validation.hpp" #include diff --git a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp index 05a0ec60..96f7a11f 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/missing_regulatory_elements_for_crosswalk.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "lib/utils.hpp" +#include "common/utils.hpp" #include "validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp" #include diff --git a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp index 1502c2a5..6d04e223 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/crosswalk/regulatory_element_details_for_crosswalks.cpp @@ -14,7 +14,7 @@ #include "validators/crosswalk/regulatory_element_details_for_crosswalks.hpp" -#include "lib/utils.hpp" +#include "common/utils.hpp" #include #include diff --git a/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp b/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp index d23c8ca5..1d48153e 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/stop_line/missing_regulatory_elements_for_stop_lines.cpp @@ -14,7 +14,7 @@ #include "validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp" -#include "lib/utils.hpp" +#include "common/utils.hpp" #include #include diff --git a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.cpp b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.cpp index b0ce0a78..91ddd4a1 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.cpp @@ -14,7 +14,7 @@ #include "validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp" -#include "lib/utils.hpp" +#include "common/utils.hpp" #include #include diff --git a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp index ace36416..fe500178 100644 --- a/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp +++ b/map/autoware_lanelet2_map_validator/src/validators/traffic_light/regulatory_element_details_for_traffic_lights.cpp @@ -14,7 +14,7 @@ #include "validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp" -#include "lib/utils.hpp" +#include "common/utils.hpp" #include From 118596e7034d1abc7d908abae2a9ade88bccf1ae Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Mon, 28 Oct 2024 18:25:55 +0900 Subject: [PATCH 42/45] Removed redundant under score Signed-off-by: TaikiYamada4 --- .../test/src/test_missing_regulatory_elements.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp index c940d3dc..7ec9f85a 100644 --- a/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp +++ b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp @@ -205,7 +205,7 @@ TEST_F(TestSuite, MissingRegulatoryElementOfCrosswalk) // NOLINT for gtest LaneletMapPtr test_map_ptr = lanelet::utils::createMap({cw_no_reg_elem}); addTestMap(test_map_ptr); - lanelet::validation::MissingRegulatoryElementsForCrosswalksValidator checker_; + lanelet::validation::MissingRegulatoryElementsForCrosswalksValidator checker; const auto & issues = checker_(*test_map_ptr); uint8_t expected_num_issues = 1; From d1e0a260b980f0ce1a8d6f1c5d99dd999f3f7a2c Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Mon, 28 Oct 2024 18:57:19 +0900 Subject: [PATCH 43/45] Removed redundant underscore again Signed-off-by: TaikiYamada4 --- .../test/src/test_missing_regulatory_elements.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp index 7ec9f85a..e8fe1cef 100644 --- a/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp +++ b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp @@ -178,8 +178,8 @@ TEST_F(TestSuite, MissingRegulatoryElementOfTrafficLight) // NOLINT for gtest LaneletMapPtr test_map_ptr = lanelet::utils::createMap({tl_no_reg_elem}); addTestMap(test_map_ptr); - lanelet::validation::MissingRegulatoryElementsForTrafficLightsValidator checker_; - const auto & issues = checker_(*test_map_ptr); + lanelet::validation::MissingRegulatoryElementsForTrafficLightsValidator checker; + const auto & issues = checker(*test_map_ptr); uint8_t expected_num_issues = 1; static constexpr const char * expected_message = @@ -206,7 +206,7 @@ TEST_F(TestSuite, MissingRegulatoryElementOfCrosswalk) // NOLINT for gtest addTestMap(test_map_ptr); lanelet::validation::MissingRegulatoryElementsForCrosswalksValidator checker; - const auto & issues = checker_(*test_map_ptr); + const auto & issues = checker(*test_map_ptr); uint8_t expected_num_issues = 1; static constexpr const char * expected_message = @@ -229,8 +229,8 @@ TEST_F(TestSuite, MissingRegulatoryElementOfStopLine) // NOLINT for gtest LaneletMapPtr test_map_ptr = lanelet::utils::createMap({sl_no_reg_elem}); addTestMap(test_map_ptr); - lanelet::validation::MissingRegulatoryElementsForStopLinesValidator checker_; - const auto & issues = checker_(*test_map_ptr); + lanelet::validation::MissingRegulatoryElementsForStopLinesValidator checker; + const auto & issues = checker(*test_map_ptr); uint8_t expected_num_issues = 1; static constexpr const char * expected_message = From 074c4f27807c4a71fba73bff48bc57ae773a6e21 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Tue, 29 Oct 2024 17:24:37 +0900 Subject: [PATCH 44/45] Changed years. Removed redundant else statement. Removed debug comments Signed-off-by: TaikiYamada4 --- .../src/common/cli.cpp | 2 +- .../src/common/cli.hpp | 2 +- .../src/common/utils.hpp | 12 +++++------- .../src/common/validation.cpp | 6 +----- .../src/common/validation.hpp | 2 +- 5 files changed, 9 insertions(+), 15 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/src/common/cli.cpp b/map/autoware_lanelet2_map_validator/src/common/cli.cpp index ee5300d4..a86dd804 100644 --- a/map/autoware_lanelet2_map_validator/src/common/cli.cpp +++ b/map/autoware_lanelet2_map_validator/src/common/cli.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 Autoware Foundation +// Copyright 2024 Autoware Foundation // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. diff --git a/map/autoware_lanelet2_map_validator/src/common/cli.hpp b/map/autoware_lanelet2_map_validator/src/common/cli.hpp index d3552604..f4d1a805 100644 --- a/map/autoware_lanelet2_map_validator/src/common/cli.hpp +++ b/map/autoware_lanelet2_map_validator/src/common/cli.hpp @@ -1,4 +1,4 @@ -// Copyright 2023 Autoware Foundation +// Copyright 2024 Autoware Foundation // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. diff --git a/map/autoware_lanelet2_map_validator/src/common/utils.hpp b/map/autoware_lanelet2_map_validator/src/common/utils.hpp index 82ab18c5..d086f30c 100644 --- a/map/autoware_lanelet2_map_validator/src/common/utils.hpp +++ b/map/autoware_lanelet2_map_validator/src/common/utils.hpp @@ -1,4 +1,4 @@ -// Copyright 2023 Autoware Foundation +// Copyright 2024 Autoware Foundation // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. @@ -45,11 +45,10 @@ void checkPrimitivesType( if (it == attrs.end() || it->second != expected_type) { issues.emplace_back(issue.severity, issue.primitive, item.id(), issue.message); const auto new_it = in_vec.erase(iter); - if (new_it != in_vec.end()) { - iter = new_it; - } else { + if (new_it == in_vec.end()) { break; } + iter = new_it; } } } @@ -69,11 +68,10 @@ void checkPrimitivesType( it_sub->second != expected_subtype) { issues.emplace_back(issue.severity, issue.primitive, item.id(), issue.message); const auto new_it = in_vec.erase(iter); - if (new_it != in_vec.end()) { - iter = new_it; - } else { + if (new_it == in_vec.end()) { break; } + iter = new_it; } } } diff --git a/map/autoware_lanelet2_map_validator/src/common/validation.cpp b/map/autoware_lanelet2_map_validator/src/common/validation.cpp index b112dbdd..f55cdc45 100644 --- a/map/autoware_lanelet2_map_validator/src/common/validation.cpp +++ b/map/autoware_lanelet2_map_validator/src/common/validation.cpp @@ -37,10 +37,8 @@ std::unique_ptr getProjector(const MetaConfig & config) lanelet::Origin{val_config.origin}); } else if (config.projector_type == projector_names::utm) { return std::make_unique(lanelet::Origin{val_config.origin}); - } else { - // std::cerr << "Set to default projector: MGRS projector" << std::endl; - return std::make_unique(); } + return std::make_unique(); } std::vector validateMap(const MetaConfig & config) @@ -55,14 +53,12 @@ std::vector validateMap(const MetaConfig & const auto & projector = getProjector(config); map = lanelet::load(cm_config.mapFile, *projector, &errors); if (!errors.empty()) { - std::cout << "!errors.empty()" << std::endl; issues.emplace_back("general", utils::transform(errors, [](auto & error) { return lanelet::validation::Issue( lanelet::validation::Severity::Error, error); })); } } catch (lanelet::LaneletError & err) { - std::cout << "catch" << std::endl; issues.emplace_back("general", utils::transform(errors, [](auto & error) { return lanelet::validation::Issue( lanelet::validation::Severity::Error, error); diff --git a/map/autoware_lanelet2_map_validator/src/common/validation.hpp b/map/autoware_lanelet2_map_validator/src/common/validation.hpp index 67e034e6..e1ca55d1 100644 --- a/map/autoware_lanelet2_map_validator/src/common/validation.hpp +++ b/map/autoware_lanelet2_map_validator/src/common/validation.hpp @@ -1,4 +1,4 @@ -// Copyright 2023 Autoware Foundation +// Copyright 2024 Autoware Foundation // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. From 2c9dca1ae149806c8039367f9a63ca259ae30b39 Mon Sep 17 00:00:00 2001 From: TaikiYamada4 Date: Wed, 30 Oct 2024 10:29:13 +0900 Subject: [PATCH 45/45] Removed underscore from test_regulatory_element_details.cpp Signed-off-by: TaikiYamada4 --- .../src/test_regulatory_element_details.cpp | 20 +++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp index 83a40a6b..6a14d51e 100644 --- a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp +++ b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp @@ -182,8 +182,8 @@ TEST_F(TestSuite, RegulatoryElementOfTrafficLightWithoutTrafficLight) // NOLINT test_map_ptr->add(tl_reg_elem_no_tl); addTestMap(test_map_ptr); - lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker_; - const auto & issues = checker_(*test_map_ptr); + lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker; + const auto & issues = checker(*test_map_ptr); uint8_t expected_num_issues = 2; static constexpr const char * expected_message1 = @@ -222,8 +222,8 @@ TEST_F(TestSuite, RegulatoryElementOfTrafficLightWithoutStopLine) // NOLINT for test_map_ptr->add(tl_reg_elem_no_sl); addTestMap(test_map_ptr); - lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker_; - const auto & issues = checker_(*test_map_ptr); + lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker; + const auto & issues = checker(*test_map_ptr); uint8_t expected_num_issues = 2; static constexpr const char * expected_message1 = @@ -267,8 +267,8 @@ TEST_F(TestSuite, RegulatoryElementOfCrosswalkWithoutPolygon) // NOLINT for gte LaneletMapPtr test_map_ptr = lanelet::utils::createMap({cw_no_poly}); addTestMap(test_map_ptr); - lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker_; - const auto & issues = checker_(*test_map_ptr); + lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; + const auto & issues = checker(*test_map_ptr); uint8_t expected_num_issues = 2; static constexpr const char * expected_message1 = @@ -309,8 +309,8 @@ TEST_F(TestSuite, RegulatoryElementOfCrosswalkWithoutStopline) // NOLINT for gt LaneletMapPtr test_map_ptr = lanelet::utils::createMap({cw_no_sl}); addTestMap(test_map_ptr); - lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker_; - const auto & issues = checker_(*test_map_ptr); + lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; + const auto & issues = checker(*test_map_ptr); uint8_t expected_num_issues = 1; static constexpr const char * expected_message = @@ -343,8 +343,8 @@ TEST_F(TestSuite, RegulatoryElementOfCrosswalkWithoutCrosswalk) // NOLINT for g addTestMap(test_map_ptr); test_map_ptr->add(reg_elem); - lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker_; - const auto & issues = checker_(*test_map_ptr); + lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; + const auto & issues = checker(*test_map_ptr); uint8_t expected_num_issues = 2; static constexpr const char * expected_message1 =