diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS index ae6c062f..d4d70f18 100644 --- a/.github/CODEOWNERS +++ b/.github/CODEOWNERS @@ -1,7 +1,7 @@ ### Automatically generated from package.xml ### autoware_dependency_checker/** yutaka.kondo@youtalk.jp bag2lanelet/** shinnosuke.hirakawa@tier4.jp taiki.tanaka@tier4.jp -common/autoware_debug_tools/** kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp yhisaki31@gmail.com +common/autoware_debug_tools/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp satoshi.ota@tier4.jp shintaro.sakoda@tier4.jp yhisaki31@gmail.com common/mission_planner_rviz_plugin/** isamu.takagi@tier4.jp common/rtc_manager_rviz_plugin/** taiki.tanaka@tier4.jp tomoya.kimura@tier4.jp common/tier4_automatic_goal_rviz_plugin/** dawid.moszynski@robotec.ai kyoichi.sugahara@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp diff --git a/common/autoware_debug_tools/autoware_debug_tools/system_performance_plotter/processing_time_plotter.py b/common/autoware_debug_tools/autoware_debug_tools/system_performance_plotter/processing_time_plotter.py index c865deff..68a4d151 100644 --- a/common/autoware_debug_tools/autoware_debug_tools/system_performance_plotter/processing_time_plotter.py +++ b/common/autoware_debug_tools/autoware_debug_tools/system_performance_plotter/processing_time_plotter.py @@ -1,5 +1,6 @@ #!/usr/bin/env python3 +from tier4_debug_msgs.msg import Float32Stamped from tier4_debug_msgs.msg import Float64Stamped from .system_performance_plotter_base import PREDEFINED_COMPONENT_NAMES @@ -11,7 +12,7 @@ class ProcessingTimePlotter(SystemPerformancePlotterBase): def check_topic(self, topic_name): if self.grep_topic_name is not None and self.grep_topic_name not in topic_name: return False - if "/processing_time_ms" not in topic_name: + if "/processing_time_ms" not in topic_name and "/exe_time_ms" not in topic_name: return False if self.component_name == "all": @@ -29,7 +30,7 @@ def check_topic(self, topic_name): return True def update_metrics_func(self, topic_name, data, date_time): - if not isinstance(data, Float64Stamped): + if not isinstance(data, Float64Stamped) and not isinstance(data, Float32Stamped): return if topic_name not in self.stamp_and_metrics: diff --git a/common/autoware_debug_tools/package.xml b/common/autoware_debug_tools/package.xml index bacaaf72..0789d6d2 100644 --- a/common/autoware_debug_tools/package.xml +++ b/common/autoware_debug_tools/package.xml @@ -7,6 +7,8 @@ Yukinari Hisaki Satoshi Ota Kosuke Takeuchi + Shintaro Sakoda + Fumiya Watanabe Apache License 2.0 diff --git a/map/autoware_lanelet2_map_validator/CMakeLists.txt b/map/autoware_lanelet2_map_validator/CMakeLists.txt index 9326b83f..084bb9a8 100644 --- a/map/autoware_lanelet2_map_validator/CMakeLists.txt +++ b/map/autoware_lanelet2_map_validator/CMakeLists.txt @@ -58,8 +58,11 @@ if(BUILD_TESTING) ) endfunction() - add_validation_test(missing_regulatory_elements) - add_validation_test(regulatory_element_details) + add_validation_test(missing_regulatory_elements_for_stop_lines) + add_validation_test(missing_regulatory_elements_for_crosswalks) + add_validation_test(missing_regulatory_elements_for_traffic_lights) + add_validation_test(regulatory_elements_details_for_crosswalks) + add_validation_test(regulatory_elements_details_for_traffic_lights) endif() ament_auto_package( 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 c96ec6d4..3f05ec7f 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 @@ -11,9 +11,9 @@ Required information for a crosswalk is written in the [Autoware documentation]( The output issue marks "lanelet" as the **primitive**, and the lanelet ID is written together as **ID**. -| 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. | +| Issue Code | Message | Severity | Description | Approach | +| --------------------------------------- | ------------------------------------------------- | -------- | ------------------------------------------------------------------------------------------- | ----------------------------------------------------------------------------------- | +| Crosswalk.MissingRegulatoryElements-001 | "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 62d003e7..5476e051 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 @@ -12,16 +12,16 @@ 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. | +| Issue Code | Message | Severity | Primitive | Description | Approach | +| -------------------------------------- | ---------------------------------------------------------------------------------------- | -------- | ------------------ | ---------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| Crosswalk.RegulatoryElementDetails-001 | "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 | +| Crosswalk.RegulatoryElementDetails-002 | "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. | +| Crosswalk.RegulatoryElementDetails-003 | "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. | +| Crosswalk.RegulatoryElementDetails-004 | "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. | +| Crosswalk.RegulatoryElementDetails-005 | "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 crosswalk. Remove the unnecessary ones. | +| Crosswalk.RegulatoryElementDetails-006 | "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 | +| Crosswalk.RegulatoryElementDetails-007 | "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.RegulatoryElementDetails-008 | "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. | ## 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 fb286208..dd8ad8e0 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 @@ -11,9 +11,9 @@ Required information for a stop line is written in the [Autoware documentation]( The output issue marks "linestring" as the **primitive**, and the linestring ID is written together as **ID**. -| 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. | +| Issue Code | Message | Severity | Description | Approach | +| -------------------------------------- | ------------------------------------------------- | -------- | ------------------------------------------------------------------------------------------- | ---------------------------------------------------------- | +| StopLine.MissingRegulatoryElements-001 | "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 4bcb311d..ae716886 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 @@ -11,9 +11,9 @@ Required information for traffic lights is written in the [Autoware documentatio The output issue marks "linestring" as the **primitive**, and the linestring ID is written together as **ID**. -| 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 regulatory element that refers to this linestring | +| Issue Code | Message | Severity | Description | Approach | +| ------------------------------------------ | ----------------------------------------------------- | -------- | ----------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------------- | +| TrafficLight.MissingRegulatoryElements-001 | "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 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 29a585d4..ee851dcb 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 @@ -12,12 +12,11 @@ This validator checks four types of issues. 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. | +| Issue Code | Message | Severity | Primitive | Description | Approach | +| ----------------------------------------- | ----------------------------------------------------------------------------- | -------- | ------------------ | -------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------- | +| TrafficLight.RegulatoryElementDetails-001 | "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. | +| TrafficLight.RegulatoryElementDetails-002 | "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. | +| TrafficLight.RegulatoryElementDetails-003 | "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 | ## Related source codes diff --git a/map/autoware_lanelet2_map_validator/src/common/map_loader.cpp b/map/autoware_lanelet2_map_validator/src/common/map_loader.cpp new file mode 100644 index 00000000..418a1e51 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/common/map_loader.cpp @@ -0,0 +1,82 @@ +// 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 "lanelet2_map_validator/map_loader.hpp" + +#include +#include + +namespace lanelet::autoware::validation +{ + +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 + +std::unique_ptr getProjector( + const std::string & projector_type, const lanelet::GPSPoint & origin) + +{ + if (projector_type == projector_names::mgrs) { + return std::make_unique(); + } + if (projector_type == projector_names::transverse_mercator) { + return std::make_unique( + lanelet::Origin{origin}); + } + if (projector_type == projector_names::utm) { + return std::make_unique(lanelet::Origin{origin}); + } + return nullptr; +} + +std::pair> +loadAndValidateMap( + const std::string & projector_type, const std::string & map_file, + const lanelet::validation::ValidationConfig & val_config) +{ + std::vector issues; + lanelet::LaneletMapPtr map{nullptr}; + lanelet::validation::Strings errors; + try { + const auto projector = getProjector(projector_type, val_config.origin); + if (!projector) { + errors.push_back("No valid map projection type specified!"); + } else { + map = lanelet::load(map_file, *projector, &errors); + } + if (!map) { + errors.push_back("Failed to load map!"); + } + issues.emplace_back("general", utils::transform(errors, [](auto & error) { + return lanelet::validation::Issue( + lanelet::validation::Severity::Error, error); + })); + } catch (lanelet::LaneletError & err) { + issues.emplace_back("general", utils::transform(errors, [](auto & error) { + return lanelet::validation::Issue( + lanelet::validation::Severity::Error, error); + })); + } + + return {map, issues}; +} + +} // namespace lanelet::autoware::validation diff --git a/map/autoware_lanelet2_map_validator/src/common/utils.cpp b/map/autoware_lanelet2_map_validator/src/common/utils.cpp new file mode 100644 index 00000000..29899017 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/common/utils.cpp @@ -0,0 +1,60 @@ +// 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 "lanelet2_map_validator/utils.hpp" + +#include +std::string snake_to_upper_camel(const std::string & snake_case) +{ + std::string camel_case; + bool capitalize_next = true; + + for (char ch : snake_case) { + if (ch == '_') { + capitalize_next = true; + } else if (ch == '.') { + camel_case += ch; + capitalize_next = true; + } else { + camel_case += capitalize_next ? std::toupper(ch) : ch; + capitalize_next = false; + } + } + return camel_case; +} + +std::string issue_code(const std::string & name, const int number) +{ + if (number < 0 || number > 999) { + throw std::out_of_range("Number for issue code must be between 0 and 999 inclusive."); + } + + // Set three digits number string + std::string id_num = std::to_string(number); + while (id_num.length() < 3) { + id_num = "0" + id_num; + } + + // Remove the first word from name + size_t pos = name.find('.'); + std::string name_without_prefix = name.substr(pos + 1); + + return snake_to_upper_camel(name_without_prefix) + '-' + id_num; +} + +std::string append_issue_code_prefix( + const std::string & name, const int number, const std::string & message) +{ + return "[" + issue_code(name, number) + "] " + message; +} diff --git a/map/autoware_lanelet2_map_validator/src/common/validation.cpp b/map/autoware_lanelet2_map_validator/src/common/validation.cpp index b3e33b8f..71d7f4fc 100644 --- a/map/autoware_lanelet2_map_validator/src/common/validation.cpp +++ b/map/autoware_lanelet2_map_validator/src/common/validation.cpp @@ -14,8 +14,6 @@ #include "lanelet2_map_validator/validation.hpp" -#include -#include #include #include @@ -23,6 +21,7 @@ #include #include #include +#include #include #include #include @@ -42,56 +41,11 @@ namespace lanelet::autoware::validation { -std::unique_ptr getProjector( - const std::string & projector_type, const lanelet::GPSPoint & origin) - +std::vector apply_validation( + const lanelet::LaneletMap & lanelet_map, const lanelet::validation::ValidationConfig & val_config) { - if (projector_type == projector_names::mgrs) { - return std::make_unique(); - } - if (projector_type == projector_names::transverse_mercator) { - return std::make_unique( - lanelet::Origin{origin}); - } - if (projector_type == projector_names::utm) { - return std::make_unique(lanelet::Origin{origin}); - } - return nullptr; -} - -std::vector validateMap( - const std::string & projector_type, const std::string & map_file, - const lanelet::validation::ValidationConfig & val_config) -{ - std::vector issues; - lanelet::LaneletMapPtr map{nullptr}; - lanelet::validation::Strings errors; - try { - const auto projector = getProjector(projector_type, val_config.origin); - if (!projector) { - errors.push_back("No valid map projection type specified!"); - } else { - map = lanelet::load(map_file, *projector, &errors); - } - if (map) { - appendIssues(issues, lanelet::validation::validateMap(*map, val_config)); - } else { - errors.push_back("Failed to load map!"); - } - if (!errors.empty()) { - issues.emplace_back("general", utils::transform(errors, [](auto & error) { - return lanelet::validation::Issue( - lanelet::validation::Severity::Error, error); - })); - } - } catch (lanelet::LaneletError & err) { - issues.emplace_back("general", utils::transform(errors, [](auto & error) { - return lanelet::validation::Issue( - lanelet::validation::Severity::Error, error); - })); - } - - return issues; + return lanelet::validation::validateMap( + const_cast(lanelet_map), val_config); } Validators parse_validators(const json & json_data) @@ -200,6 +154,7 @@ std::vector describe_unused_validators_to_j issue_json["primitive"] = lanelet::validation::toString(lanelet::validation::Primitive::Primitive); issue_json["id"] = 0; + issue_json["issue_code"] = "General.InvalidPrerequisites-001"; issue_json["message"] = "Prerequisites don't exist OR they are making a loop."; issues_json.push_back(issue_json); validator_json["issues"] = issues_json; @@ -213,7 +168,7 @@ std::vector describe_unused_validators_to_j } if (issues.size() > 0) { - detected_issues.push_back({"invalid_prerequisites", issues}); + detected_issues.push_back({"general.invalid_prerequisites", issues}); } return detected_issues; } @@ -243,7 +198,7 @@ std::vector check_prerequisite_completion( issue.severity = lanelet::validation::Severity::Error; issue.primitive = lanelet::validation::Primitive::Primitive; issue.id = lanelet::InvalId; - issue.message = "Prerequisites didn't pass"; + issue.message = "[General.PrerequisitesFailure-001] Prerequisites didn't pass."; issues.push_back(issue); } @@ -326,9 +281,11 @@ lanelet::validation::ValidationConfig replace_validator( return temp; } -void process_requirements(json json_data, const MetaConfig & validator_config) +void process_requirements( + json json_data, const MetaConfig & validator_config, const lanelet::LaneletMap & lanelet_map) { - std::vector issues; + std::vector total_issues; + std::regex issue_code_pattern(R"(\[(.+?)\]\s*(.+))"); // List up validators in order Validators validators = parse_validators(json_data); @@ -338,49 +295,53 @@ void process_requirements(json json_data, const MetaConfig & validator_config) if (auto unused_validator_issues = describe_unused_validators_to_json(json_data, remaining_validators); !unused_validator_issues.empty()) { - appendIssues(issues, std::move(unused_validator_issues)); + appendIssues(total_issues, std::move(unused_validator_issues)); } // Main validation process while (!validation_queue.empty()) { - std::string validator_name = validation_queue.front(); + const std::string validator_name = validation_queue.front(); validation_queue.pop(); - std::vector temp_issues; - // Check prerequisites are OK - appendIssues(temp_issues, check_prerequisite_completion(validators, validator_name)); - - if (temp_issues.size() == 0) { - // Validate map - appendIssues( - temp_issues, - validateMap( - validator_config.projector_type, validator_config.command_line_config.mapFile, - replace_validator( - validator_config.command_line_config.validationConfig, validator_name))); - } + const auto prerequisite_issues = check_prerequisite_completion(validators, validator_name); + appendIssues(total_issues, prerequisite_issues); + + // NOTE: if prerequisite_issues is not empty, skip the content validation process + const auto issues = + prerequisite_issues.empty() + ? apply_validation( + lanelet_map, replace_validator( + validator_config.command_line_config.validationConfig, validator_name)) + : std::vector(); // Add validation results to the json data json & validator_json = find_validator_block(json_data, validator_name); - if (temp_issues.size() == 0) { + if (issues.empty()) { validator_json["passed"] = true; continue; } - if (temp_issues[0].warnings().size() + temp_issues[0].errors().size() == 0) { + if (issues[0].warnings().size() + issues[0].errors().size() == 0) { validator_json["passed"] = true; } else { validator_json["passed"] = false; } - if (temp_issues[0].issues.size() > 0) { + if (!issues[0].issues.empty()) { json issues_json; - for (const auto & issue : temp_issues[0].issues) { + for (const auto & issue : issues[0].issues) { + std::smatch matches; 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; + if (std::regex_match(issue.message, matches, issue_code_pattern)) { + issue_json["issue_code"] = matches[1]; + issue_json["message"] = matches[2]; + } else { + // Issue messages not matching the issue code format will be output as it is + issue_json["message"] = issue.message; + } issues_json.push_back(issue_json); if ( @@ -392,12 +353,12 @@ void process_requirements(json json_data, const MetaConfig & validator_config) } validator_json["issues"] = issues_json; } - appendIssues(issues, std::move(temp_issues)); + appendIssues(total_issues, issues); } // Show results summarize_validator_results(json_data); - lanelet::validation::printAllIssues(issues); + lanelet::validation::printAllIssues(total_issues); // Save results if (!validator_config.output_file_path.empty()) { diff --git a/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/map_loader.hpp b/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/map_loader.hpp new file mode 100644 index 00000000..0ae5e7e5 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/map_loader.hpp @@ -0,0 +1,37 @@ +// 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 LANELET2_MAP_VALIDATOR__MAP_LOADER_HPP_ // NOLINT +#define LANELET2_MAP_VALIDATOR__MAP_LOADER_HPP_ // NOLINT + +#include +#include +#include + +#include +#include +#include +#include + +namespace lanelet::autoware::validation +{ + +std::pair> +loadAndValidateMap( + const std::string & projector_type, const std::string & map_file, + const lanelet::validation::ValidationConfig & val_config); + +} // namespace lanelet::autoware::validation + +#endif // LANELET2_MAP_VALIDATOR__MAP_LOADER_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/utils.hpp b/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/utils.hpp index db93c2a4..ec1bffe5 100644 --- a/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/utils.hpp +++ b/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/utils.hpp @@ -19,14 +19,21 @@ #include #include +#include #include namespace lanelet::autoware::validation { -template -void appendIssues(std::vector & to, std::vector && from) +template +auto appendIssues(std::vector & to, Container && from) -> + typename std::enable_if_t::value_type>, void> { - to.insert(to.end(), std::make_move_iterator(from.begin()), std::make_move_iterator(from.end())); + if constexpr (std::is_rvalue_reference::value) { + to.insert(to.end(), std::make_move_iterator(from.begin()), std::make_move_iterator(from.end())); + } + if constexpr (std::is_lvalue_reference::value) { + to.insert(to.end(), from.begin(), from.end()); + } } template @@ -74,4 +81,9 @@ void checkPrimitivesType( } // namespace lanelet::autoware::validation +std::string snake_to_upper_camel(const std::string & snake_case); +std::string issue_code(const std::string & name, const int number); +std::string append_issue_code_prefix( + const std::string & name, const int number, const std::string & message); + #endif // LANELET2_MAP_VALIDATOR__UTILS_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validation.hpp b/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validation.hpp index fb90dffd..273ea639 100644 --- a/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validation.hpp +++ b/map/autoware_lanelet2_map_validator/src/include/lanelet2_map_validator/validation.hpp @@ -20,12 +20,9 @@ #include -#include -#include #include #include -#include #include #include #include @@ -36,16 +33,6 @@ using json = nlohmann::json; -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::autoware::validation { struct ValidatorInfo @@ -58,11 +45,8 @@ struct ValidatorInfo using Validators = std::unordered_map; -std::unique_ptr getProjector( - const std::string & projector_type, const lanelet::GPSPoint & origin); - -std::vector validateMap( - const std::string & projector_type, const std::string & map_file, +std::vector apply_validation( + const lanelet::LaneletMap & lanelet_map, const lanelet::validation::ValidationConfig & val_config); Validators parse_validators(const json & json_data); @@ -85,7 +69,8 @@ lanelet::validation::ValidationConfig replace_validator( const lanelet::validation::ValidationConfig & input, const std::string & validator_name); void process_requirements( - json json_data, const lanelet::autoware::validation::MetaConfig & validator_config); + json json_data, const lanelet::autoware::validation::MetaConfig & validator_config, + const lanelet::LaneletMap & lanelet_map); } // namespace lanelet::autoware::validation #endif // LANELET2_MAP_VALIDATOR__VALIDATION_HPP_ diff --git a/map/autoware_lanelet2_map_validator/src/main.cpp b/map/autoware_lanelet2_map_validator/src/main.cpp index 9c97bf06..66918b0d 100644 --- a/map/autoware_lanelet2_map_validator/src/main.cpp +++ b/map/autoware_lanelet2_map_validator/src/main.cpp @@ -13,6 +13,7 @@ // limitations under the License. #include "lanelet2_map_validator/cli.hpp" +#include "lanelet2_map_validator/map_loader.hpp" #include "lanelet2_map_validator/utils.hpp" #include "lanelet2_map_validator/validation.hpp" @@ -53,22 +54,27 @@ int main(int argc, char * argv[]) // Validation start 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)) { + } + 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!"); } + const auto [lanelet_map_ptr, map_issue] = lanelet::autoware::validation::loadAndValidateMap( + meta_config.projector_type, meta_config.command_line_config.mapFile, + meta_config.command_line_config.validationConfig); - if (!meta_config.requirements_file.empty()) { + if (!lanelet_map_ptr) { + lanelet::validation::printAllIssues(map_issue); + } else 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!"); } std::ifstream input_file(meta_config.requirements_file); json json_data; input_file >> json_data; - lanelet::autoware::validation::process_requirements(json_data, meta_config); + lanelet::autoware::validation::process_requirements(json_data, meta_config, *lanelet_map_ptr); } else { - auto issues = lanelet::autoware::validation::validateMap( - meta_config.projector_type, meta_config.command_line_config.mapFile, - meta_config.command_line_config.validationConfig); + const auto issues = lanelet::autoware::validation::apply_validation( + *lanelet_map_ptr, meta_config.command_line_config.validationConfig); lanelet::validation::printAllIssues(issues); } 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 36716c14..a21b1c09 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 @@ -83,7 +83,8 @@ MissingRegulatoryElementsForCrosswalksValidator::checkMissingRegulatoryElementsF 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."); + append_issue_code_prefix( + this->name(), 1, "No regulatory element refers to this crosswalk.")); } } 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 6ac4bf06..983c2933 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 @@ -61,34 +61,46 @@ RegulatoryElementsDetailsForCrosswalksValidator::checkRegulatoryElementOfCrosswa auto crosswalk_polygons = elem->getParameters( lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon); - // Report warning if regulatory element does not have crosswalk polygon - if (crosswalk_polygons.empty()) { + // Report error if regulatory element does not have lanelet of crosswalk + if (refers.empty()) { issues.emplace_back( - lanelet::validation::Severity::Warning, lanelet::validation::Primitive::RegulatoryElement, - 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 + lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), + append_issue_code_prefix( + this->name(), 1, + "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 crosswalk must have only one crosswalk_polygon."); + elem->id(), + append_issue_code_prefix( + this->name(), 2, + "Regulatory element of crosswalk must have only one lanelet of crosswalk(refers).")); } // 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 crosswalk does not have stop line(ref_line)."); + elem->id(), + append_issue_code_prefix( + this->name(), 3, "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()) { + // Report warning if regulatory element does not have crosswalk polygon + if (crosswalk_polygons.empty()) { issues.emplace_back( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, - 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 + lanelet::validation::Severity::Warning, lanelet::validation::Primitive::RegulatoryElement, + elem->id(), + append_issue_code_prefix( + this->name(), 4, "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 crosswalk must have only one lanelet of crosswalk(refers)."); + append_issue_code_prefix( + this->name(), 5, + "Regulatory element of crosswalk must have only one crosswalk_polygon.")); } // If this is a crosswalk type regulatory element, the "refers" has to be a "crosswalk" subtype @@ -96,7 +108,8 @@ RegulatoryElementsDetailsForCrosswalksValidator::checkRegulatoryElementOfCrosswa 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."); + append_issue_code_prefix( + this->name(), 6, "Refers of crosswalk regulatory element must have type of crosswalk.")); lanelet::autoware::validation::checkPrimitivesType( refers, lanelet::AttributeValueString::Lanelet, lanelet::AttributeValueString::Crosswalk, issue_cw, issues); @@ -106,7 +119,8 @@ RegulatoryElementsDetailsForCrosswalksValidator::checkRegulatoryElementOfCrosswa const auto & issue_sl = lanelet::validation::Issue( lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, lanelet::utils::getId(), - "ref_line of crosswalk regulatory element must have type of stopline."); + append_issue_code_prefix( + this->name(), 7, "ref_line of crosswalk regulatory element must have type of stopline.")); lanelet::autoware::validation::checkPrimitivesType( ref_lines, lanelet::AttributeValueString::StopLine, issue_sl, issues); @@ -115,7 +129,9 @@ RegulatoryElementsDetailsForCrosswalksValidator::checkRegulatoryElementOfCrosswa 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."); + append_issue_code_prefix( + this->name(), 8, + "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); 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 1f9aa2f1..0af22b4d 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 @@ -93,7 +93,8 @@ MissingRegulatoryElementsForStopLinesValidator::checkMissingRegulatoryElementsFo 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."); + append_issue_code_prefix( + this->name(), 1, "No regulatory element refers to this stop line.")); } } 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 2ad34356..ad07611f 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 @@ -83,7 +83,8 @@ MissingRegulatoryElementsForTrafficLightsValidator::checkMissingRegulatoryElemen 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."); + append_issue_code_prefix( + this->name(), 1, "No regulatory element refers to this traffic light.")); } } 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 d163f3a1..4c536d03 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 @@ -71,11 +71,6 @@ RegulatoryElementsDetailsForTrafficLightsValidator::checkRegulatoryElementOfTraf // Get stop line referred by regulatory element auto ref_lines = elem->getParameters(lanelet::RoleName::RefLine); - 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( @@ -89,20 +84,26 @@ RegulatoryElementsDetailsForTrafficLightsValidator::checkRegulatoryElementOfTraf 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)."); + elem->id(), + append_issue_code_prefix( + this->name(), 1, "Regulatory element of traffic light must have a stop line(ref_line).")); } 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."); + append_issue_code_prefix( + this->name(), 2, + "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(), - "ref_line of traffic light regulatory element must have type of stop_line."); + append_issue_code_prefix( + this->name(), 3, + "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/test/data/test_describe_unused_validators_input.json b/map/autoware_lanelet2_map_validator/test/data/json/test_describe_unused_validators_input.json similarity index 100% rename from map/autoware_lanelet2_map_validator/test/data/test_describe_unused_validators_input.json rename to map/autoware_lanelet2_map_validator/test/data/json/test_describe_unused_validators_input.json diff --git a/map/autoware_lanelet2_map_validator/test/data/test_describe_unused_validators_output.json b/map/autoware_lanelet2_map_validator/test/data/json/test_describe_unused_validators_output.json similarity index 87% rename from map/autoware_lanelet2_map_validator/test/data/test_describe_unused_validators_output.json rename to map/autoware_lanelet2_map_validator/test/data/json/test_describe_unused_validators_output.json index 5bdaec9e..30d17f0e 100644 --- a/map/autoware_lanelet2_map_validator/test/data/test_describe_unused_validators_output.json +++ b/map/autoware_lanelet2_map_validator/test/data/json/test_describe_unused_validators_output.json @@ -16,6 +16,7 @@ "severity": "Error", "primitive": "primitive", "id": 0, + "issue_code": "General.InvalidPrerequisites-001", "message": "Prerequisites don't exist OR they are making a loop." } ] @@ -33,6 +34,7 @@ "severity": "Error", "primitive": "primitive", "id": 0, + "issue_code": "General.InvalidPrerequisites-001", "message": "Prerequisites don't exist OR they are making a loop." } ] @@ -50,6 +52,7 @@ "severity": "Error", "primitive": "primitive", "id": 0, + "issue_code": "General.InvalidPrerequisites-001", "message": "Prerequisites don't exist OR they are making a loop." } ] diff --git a/map/autoware_lanelet2_map_validator/test/data/test_input.json b/map/autoware_lanelet2_map_validator/test/data/json/test_input.json similarity index 100% rename from map/autoware_lanelet2_map_validator/test/data/test_input.json rename to map/autoware_lanelet2_map_validator/test/data/json/test_input.json diff --git a/map/autoware_lanelet2_map_validator/test/data/test_summarize_validator_results_input.json b/map/autoware_lanelet2_map_validator/test/data/json/test_summarize_validator_results_input.json similarity index 92% rename from map/autoware_lanelet2_map_validator/test/data/test_summarize_validator_results_input.json rename to map/autoware_lanelet2_map_validator/test/data/json/test_summarize_validator_results_input.json index 90312901..d8f28704 100644 --- a/map/autoware_lanelet2_map_validator/test/data/test_summarize_validator_results_input.json +++ b/map/autoware_lanelet2_map_validator/test/data/json/test_summarize_validator_results_input.json @@ -33,6 +33,7 @@ "severity": "Error", "primitive": "primitive", "id": 0, + "issue_code": "General.InvalidPrerequisites-001", "message": "Prerequisites don't exist OR they are making a loop." } ] diff --git a/map/autoware_lanelet2_map_validator/test/data/test_summarize_validator_results_output.json b/map/autoware_lanelet2_map_validator/test/data/json/test_summarize_validator_results_output.json similarity index 93% rename from map/autoware_lanelet2_map_validator/test/data/test_summarize_validator_results_output.json rename to map/autoware_lanelet2_map_validator/test/data/json/test_summarize_validator_results_output.json index b925fadf..dba3ea36 100644 --- a/map/autoware_lanelet2_map_validator/test/data/test_summarize_validator_results_output.json +++ b/map/autoware_lanelet2_map_validator/test/data/json/test_summarize_validator_results_output.json @@ -35,6 +35,7 @@ "severity": "Error", "primitive": "primitive", "id": 0, + "issue_code": "General.InvalidPrerequisites-001", "message": "Prerequisites don't exist OR they are making a loop." } ] diff --git a/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_regulatory_element_with_multiple_refers.osm b/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_regulatory_element_with_multiple_refers.osm new file mode 100644 index 00000000..1a323f1f --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_regulatory_element_with_multiple_refers.osm @@ -0,0 +1,225 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_regulatory_element_without_refers.osm b/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_regulatory_element_without_refers.osm new file mode 100644 index 00000000..ebde6f25 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_regulatory_element_without_refers.osm @@ -0,0 +1,181 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_with_multiple_polygons.osm b/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_with_multiple_polygons.osm new file mode 100644 index 00000000..8c0b1045 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_with_multiple_polygons.osm @@ -0,0 +1,211 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_with_regulatory_element.osm b/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_with_regulatory_element.osm new file mode 100644 index 00000000..f04754cd --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_with_regulatory_element.osm @@ -0,0 +1,182 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_with_wrong_polygon_type.osm b/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_with_wrong_polygon_type.osm new file mode 100644 index 00000000..91f8e94d --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_with_wrong_polygon_type.osm @@ -0,0 +1,182 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_with_wrong_ref_line_type.osm b/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_with_wrong_ref_line_type.osm new file mode 100644 index 00000000..04c22b6e --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_with_wrong_ref_line_type.osm @@ -0,0 +1,182 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_with_wrong_refers_type.osm b/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_with_wrong_refers_type.osm new file mode 100644 index 00000000..e747632c --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_with_wrong_refers_type.osm @@ -0,0 +1,182 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_without_polygon.osm b/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_without_polygon.osm new file mode 100644 index 00000000..01a2a61d --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_without_polygon.osm @@ -0,0 +1,173 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_without_regulatory_elements.osm b/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_without_regulatory_elements.osm new file mode 100644 index 00000000..86f9909d --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_without_regulatory_elements.osm @@ -0,0 +1,172 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_without_stop_line.osm b/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_without_stop_line.osm new file mode 100644 index 00000000..37dab629 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/data/map/crosswalk/crosswalk_without_stop_line.osm @@ -0,0 +1,168 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/map/autoware_lanelet2_map_validator/test/data/map/sample_map.osm b/map/autoware_lanelet2_map_validator/test/data/map/sample_map.osm new file mode 100644 index 00000000..e9b84e91 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/data/map/sample_map.osm @@ -0,0 +1,5974 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/map/autoware_lanelet2_map_validator/test/data/map/stop_line/stop_line_with_road_marking.osm b/map/autoware_lanelet2_map_validator/test/data/map/stop_line/stop_line_with_road_marking.osm new file mode 100644 index 00000000..6aacac40 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/data/map/stop_line/stop_line_with_road_marking.osm @@ -0,0 +1,291 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/map/autoware_lanelet2_map_validator/test/data/map/stop_line/stop_line_with_traffic_sign.osm b/map/autoware_lanelet2_map_validator/test/data/map/stop_line/stop_line_with_traffic_sign.osm new file mode 100644 index 00000000..6526a5b1 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/data/map/stop_line/stop_line_with_traffic_sign.osm @@ -0,0 +1,73 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/map/autoware_lanelet2_map_validator/test/data/map/stop_line/stop_line_without_regulatory_elements.osm b/map/autoware_lanelet2_map_validator/test/data/map/stop_line/stop_line_without_regulatory_elements.osm new file mode 100644 index 00000000..d5819710 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/data/map/stop_line/stop_line_without_regulatory_elements.osm @@ -0,0 +1,50 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/map/autoware_lanelet2_map_validator/test/data/map/traffic_light/traffic_light_regulatory_element_without_ref_line.osm b/map/autoware_lanelet2_map_validator/test/data/map/traffic_light/traffic_light_regulatory_element_without_ref_line.osm new file mode 100644 index 00000000..ce5de81f --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/data/map/traffic_light/traffic_light_regulatory_element_without_ref_line.osm @@ -0,0 +1,410 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/map/autoware_lanelet2_map_validator/test/data/map/traffic_light/traffic_light_regulatory_element_without_refers.osm b/map/autoware_lanelet2_map_validator/test/data/map/traffic_light/traffic_light_regulatory_element_without_refers.osm new file mode 100644 index 00000000..cd743f66 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/data/map/traffic_light/traffic_light_regulatory_element_without_refers.osm @@ -0,0 +1,410 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/map/autoware_lanelet2_map_validator/test/data/map/traffic_light/traffic_light_with_regulatory_element.osm b/map/autoware_lanelet2_map_validator/test/data/map/traffic_light/traffic_light_with_regulatory_element.osm new file mode 100644 index 00000000..9d4757d5 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/data/map/traffic_light/traffic_light_with_regulatory_element.osm @@ -0,0 +1,411 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/map/autoware_lanelet2_map_validator/test/data/map/traffic_light/traffic_light_with_wrong_ref_line_type.osm b/map/autoware_lanelet2_map_validator/test/data/map/traffic_light/traffic_light_with_wrong_ref_line_type.osm new file mode 100644 index 00000000..48d2d565 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/data/map/traffic_light/traffic_light_with_wrong_ref_line_type.osm @@ -0,0 +1,411 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/map/autoware_lanelet2_map_validator/test/data/map/traffic_light/traffic_light_with_wrong_refers_type.osm b/map/autoware_lanelet2_map_validator/test/data/map/traffic_light/traffic_light_with_wrong_refers_type.osm new file mode 100644 index 00000000..aa2a40a0 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/data/map/traffic_light/traffic_light_with_wrong_refers_type.osm @@ -0,0 +1,411 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/map/autoware_lanelet2_map_validator/test/data/map/traffic_light/traffic_light_without_regulatory_element.osm b/map/autoware_lanelet2_map_validator/test/data/map/traffic_light/traffic_light_without_regulatory_element.osm new file mode 100644 index 00000000..4395f440 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/data/map/traffic_light/traffic_light_without_regulatory_element.osm @@ -0,0 +1,402 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/map/autoware_lanelet2_map_validator/test/example_requirement_set.json b/map/autoware_lanelet2_map_validator/test/example_requirement_set.json deleted file mode 100644 index 445be17a..00000000 --- a/map/autoware_lanelet2_map_validator/test/example_requirement_set.json +++ /dev/null @@ -1,35 +0,0 @@ -{ - "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/src/map_validation_tester.hpp b/map/autoware_lanelet2_map_validator/test/src/map_validation_tester.hpp new file mode 100644 index 00000000..6fc142dd --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/src/map_validation_tester.hpp @@ -0,0 +1,48 @@ +// 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 MAP_VALIDATION_TESTER_HPP_ +#define MAP_VALIDATION_TESTER_HPP_ + +#include +#include + +#include +#include + +#include +#include +#include + +class MapValidationTester : public ::testing::Test +{ +protected: + void load_target_map(std::string file_name) + { + const auto projector = std::make_unique(); + + std::string package_share_directory = + ament_index_cpp::get_package_share_directory("autoware_lanelet2_map_validator"); + + map_ = lanelet::load( + package_share_directory + "/data/map/" + file_name, *projector, &loading_errors_); + + EXPECT_NE(map_, nullptr); + } + + lanelet::LaneletMapPtr map_{nullptr}; + std::vector loading_errors_; +}; + +#endif // MAP_VALIDATION_TESTER_HPP_ diff --git a/map/autoware_lanelet2_map_validator/test/src/test_json_processing.cpp b/map/autoware_lanelet2_map_validator/test/src/test_json_processing.cpp index 235f027a..0ae1b1ff 100644 --- a/map/autoware_lanelet2_map_validator/test/src/test_json_processing.cpp +++ b/map/autoware_lanelet2_map_validator/test/src/test_json_processing.cpp @@ -37,7 +37,7 @@ class JsonProcessingTest : public ::testing::Test { std::string package_share_directory = ament_index_cpp::get_package_share_directory("autoware_lanelet2_map_validator"); - std::ifstream file(package_share_directory + "/data/" + file_name); + std::ifstream file(package_share_directory + "/data/json/" + file_name); EXPECT_TRUE(file.is_open()) << "Failed to open test JSON file."; json json_data; @@ -128,7 +128,7 @@ TEST_F(JsonProcessingTest, DescribeUnusedValidatorsToJson) auto detected_issues = describe_unused_validators_to_json(sample_input_data, error_validators); EXPECT_EQ(detected_issues.size(), 1); EXPECT_EQ(detected_issues[0].issues.size(), 3); - EXPECT_EQ(detected_issues[0].checkName, "invalid_prerequisites"); + EXPECT_EQ(detected_issues[0].checkName, "general.invalid_prerequisites"); EXPECT_EQ(detected_issues[0].issues[0].severity, lanelet::validation::Severity::Error); EXPECT_EQ(detected_issues[0].issues[1].severity, lanelet::validation::Severity::Error); EXPECT_EQ(detected_issues[0].issues[2].severity, lanelet::validation::Severity::Error); 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 deleted file mode 100644 index b804003e..00000000 --- a/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements.cpp +++ /dev/null @@ -1,245 +0,0 @@ -// 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 "lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp" -#include "lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp" -#include "lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp" - -#include -#include - -#include -#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_; - -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(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()); - - 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::autoware::validation::MissingRegulatoryElementsForCrosswalksValidator::name(), - lanelet::autoware::validation::MissingRegulatoryElementsForStopLinesValidator::name(), - lanelet::autoware::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; - } -} - -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); - - lanelet::autoware::validation::MissingRegulatoryElementsForTrafficLightsValidator checker; - 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."; - 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); - - lanelet::autoware::validation::MissingRegulatoryElementsForCrosswalksValidator checker; - 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."; - 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); - - lanelet::autoware::validation::MissingRegulatoryElementsForStopLinesValidator checker; - 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."; - 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_missing_regulatory_elements_for_crosswalks.cpp b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements_for_crosswalks.cpp new file mode 100644 index 00000000..17ec1714 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements_for_crosswalks.cpp @@ -0,0 +1,74 @@ +// 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 "lanelet2_map_validator/validators/crosswalk/missing_regulatory_elements_for_crosswalks.hpp" +#include "map_validation_tester.hpp" + +#include +#include + +class TestMissingRegulatoryElementsForCrosswalks : public MapValidationTester +{ +private: +}; + +TEST_F(TestMissingRegulatoryElementsForCrosswalks, ValidatorAvailability) // NOLINT for gtest +{ + std::string expected_validator_name = + lanelet::autoware::validation::MissingRegulatoryElementsForCrosswalksValidator::name(); + + lanelet::validation::Strings validators = + lanelet::validation::availabeChecks(expected_validator_name); // cspell:disable-line + + const uint32_t expected_validator_num = 1; + EXPECT_EQ(expected_validator_num, validators.size()); + EXPECT_EQ(expected_validator_name, validators[0]); +} + +TEST_F(TestMissingRegulatoryElementsForCrosswalks, MissingRegulatoryElement) // NOLINT for gtest +{ + load_target_map("crosswalk/crosswalk_without_regulatory_elements.osm"); + + lanelet::autoware::validation::MissingRegulatoryElementsForCrosswalksValidator checker; + const auto & issues = checker(*map_); + + EXPECT_EQ(issues.size(), 1); + EXPECT_EQ(issues[0].id, 18); + EXPECT_EQ(issues[0].severity, lanelet::validation::Severity::Error); + EXPECT_EQ(issues[0].primitive, lanelet::validation::Primitive::Lanelet); + EXPECT_EQ( + issues[0].message, + "[Crosswalk.MissingRegulatoryElements-001] No regulatory element refers to this " + "crosswalk."); +} + +TEST_F(TestMissingRegulatoryElementsForCrosswalks, RegulatoryElementExists) // NOLINT for gtest +{ + load_target_map("crosswalk/crosswalk_with_regulatory_element.osm"); + + lanelet::autoware::validation::MissingRegulatoryElementsForCrosswalksValidator checker; + const auto & issues = checker(*map_); + + EXPECT_EQ(issues.size(), 0); +} + +TEST_F(TestMissingRegulatoryElementsForCrosswalks, SampleMap) // NOLINT for gtest +{ + load_target_map("sample_map.osm"); + + lanelet::autoware::validation::MissingRegulatoryElementsForCrosswalksValidator checker; + const auto & issues = checker(*map_); + + EXPECT_EQ(issues.size(), 0); +} diff --git a/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements_for_stop_lines.cpp b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements_for_stop_lines.cpp new file mode 100644 index 00000000..006ac806 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements_for_stop_lines.cpp @@ -0,0 +1,83 @@ +// 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 "lanelet2_map_validator/validators/stop_line/missing_regulatory_elements_for_stop_lines.hpp" +#include "map_validation_tester.hpp" + +#include +#include + +class TestMissingRegulatoryElementsForStopLines : public MapValidationTester +{ +private: +}; + +TEST_F(TestMissingRegulatoryElementsForStopLines, ValidatorAvailability) // NOLINT for gtest +{ + std::string expected_validator_name = + lanelet::autoware::validation::MissingRegulatoryElementsForStopLinesValidator::name(); + + lanelet::validation::Strings validators = + lanelet::validation::availabeChecks(expected_validator_name); // cspell:disable-line + + const uint32_t expected_validator_num = 1; + EXPECT_EQ(expected_validator_num, validators.size()); + EXPECT_EQ(expected_validator_name, validators[0]); +} + +TEST_F(TestMissingRegulatoryElementsForStopLines, MissingRegulatoryElement) // NOLINT for gtest +{ + load_target_map("stop_line/stop_line_without_regulatory_elements.osm"); + + lanelet::autoware::validation::MissingRegulatoryElementsForStopLinesValidator checker; + const auto & issues = checker(*map_); + + EXPECT_EQ(issues.size(), 1); + EXPECT_EQ(issues[0].id, 2156); + EXPECT_EQ(issues[0].severity, lanelet::validation::Severity::Error); + EXPECT_EQ(issues[0].primitive, lanelet::validation::Primitive::LineString); + EXPECT_EQ( + issues[0].message, + "[StopLine.MissingRegulatoryElements-001] No regulatory element refers to this stop line."); +} + +TEST_F(TestMissingRegulatoryElementsForStopLines, TrafficSignRegulatoryElement) // NOLINT for gtest +{ + load_target_map("stop_line/stop_line_with_traffic_sign.osm"); + + lanelet::autoware::validation::MissingRegulatoryElementsForStopLinesValidator checker; + const auto & issues = checker(*map_); + + EXPECT_EQ(issues.size(), 0); +} + +TEST_F(TestMissingRegulatoryElementsForStopLines, RoadMarkingRegulatoryElement) // NOLINT for gtest +{ + load_target_map("stop_line/stop_line_with_road_marking.osm"); + + lanelet::autoware::validation::MissingRegulatoryElementsForStopLinesValidator checker; + const auto & issues = checker(*map_); + + EXPECT_EQ(issues.size(), 0); +} + +TEST_F(TestMissingRegulatoryElementsForStopLines, SampleMap) // NOLINT for gtest +{ + load_target_map("sample_map.osm"); + + lanelet::autoware::validation::MissingRegulatoryElementsForStopLinesValidator checker; + const auto & issues = checker(*map_); + + EXPECT_EQ(issues.size(), 0); +} diff --git a/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements_for_traffic_lights.cpp b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements_for_traffic_lights.cpp new file mode 100644 index 00000000..3c3d2ae4 --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/src/test_missing_regulatory_elements_for_traffic_lights.cpp @@ -0,0 +1,74 @@ +// 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 "lanelet2_map_validator/validators/traffic_light/missing_regulatory_elements_for_traffic_lights.hpp" +#include "map_validation_tester.hpp" + +#include +#include + +class TestMissingRegulatoryElementsForTrafficLights : public MapValidationTester +{ +private: +}; + +TEST_F(TestMissingRegulatoryElementsForTrafficLights, ValidatorAvailability) // NOLINT for gtest +{ + std::string expected_validator_name = + lanelet::autoware::validation::MissingRegulatoryElementsForTrafficLightsValidator::name(); + + lanelet::validation::Strings validators = + lanelet::validation::availabeChecks(expected_validator_name); // cspell:disable-line + + const uint32_t expected_validator_num = 1; + EXPECT_EQ(expected_validator_num, validators.size()); + EXPECT_EQ(expected_validator_name, validators[0]); +} + +TEST_F(TestMissingRegulatoryElementsForTrafficLights, MissingRegulatoryElement) // NOLINT for gtest +{ + load_target_map("traffic_light/traffic_light_without_regulatory_element.osm"); + + lanelet::autoware::validation::MissingRegulatoryElementsForTrafficLightsValidator checker; + const auto & issues = checker(*map_); + + EXPECT_EQ(issues.size(), 1); + EXPECT_EQ(issues[0].id, 416); + EXPECT_EQ(issues[0].severity, lanelet::validation::Severity::Error); + EXPECT_EQ(issues[0].primitive, lanelet::validation::Primitive::LineString); + EXPECT_EQ( + issues[0].message, + "[TrafficLight.MissingRegulatoryElements-001] No regulatory element refers to this traffic " + "light."); +} + +TEST_F(TestMissingRegulatoryElementsForTrafficLights, RegulatoryElementExists) // NOLINT for gtest +{ + load_target_map("traffic_light/traffic_light_with_regulatory_element.osm"); + + lanelet::autoware::validation::MissingRegulatoryElementsForTrafficLightsValidator checker; + const auto & issues = checker(*map_); + + EXPECT_EQ(issues.size(), 0); +} + +TEST_F(TestMissingRegulatoryElementsForTrafficLights, SampleMap) // NOLINT for gtest +{ + load_target_map("sample_map.osm"); + + lanelet::autoware::validation::MissingRegulatoryElementsForTrafficLightsValidator checker; + const auto & issues = checker(*map_); + + EXPECT_EQ(issues.size(), 0); +} 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 deleted file mode 100644 index 7346576c..00000000 --- a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp +++ /dev/null @@ -1,336 +0,0 @@ -// 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 "lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp" -#include "lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp" - -#include -#include - -#include -#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; - -private: -}; - -TEST_F(TestSuite, ValidatorAvailability) // NOLINT for gtest -{ - std::string expected_validators_concat = - "mapping.crosswalk.regulatory_element_details," - "mapping.traffic_light.regulatory_element_details"; - - lanelet::validation::Strings validators = - 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()); - - std::set expected_validators_set = { - "mapping.crosswalk.regulatory_element_details", - "mapping.traffic_light.regulatory_element_details"}; - - std::set testing_validators_set = { - lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator::name(), - lanelet::autoware::validation::RegulatoryElementsDetailsForTrafficLightsValidator::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; - } -} - -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); - - lanelet::autoware::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker; - const auto & issues = checker(*test_map_ptr); - - uint8_t expected_num_issues = 1; - static constexpr const char * expected_message1 = - "Refers of traffic light regulatory element must have type of traffic_light."; - 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); - } - } -} - -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); - - lanelet::autoware::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker; - const auto & issues = checker(*test_map_ptr); - - uint8_t expected_num_issues = 1; - static constexpr const char * expected_message1 = - "ref_line of traffic light regulatory element must have type of stop_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); - } - } -} - -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 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), - {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); - - lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; - const auto & issues = checker(*test_map_ptr); - - uint8_t expected_num_issues = 1; - static constexpr const char * expected_message1 = - "Crosswalk polygon of crosswalk regulatory element must have type of 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); - } - } -} - -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); - - lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; - const auto & issues = checker(*test_map_ptr); - - uint8_t expected_num_issues = 1; - static constexpr const char * expected_message = - "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); - 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); - - lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; - const auto & issues = checker(*test_map_ptr); - - uint8_t expected_num_issues = 1; - static constexpr const char * expected_message1 = - "Refers of crosswalk regulatory element must have type of crosswalk."; - 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); - } - } -} diff --git a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_elements_details_for_crosswalks.cpp b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_elements_details_for_crosswalks.cpp new file mode 100644 index 00000000..b49406fd --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_elements_details_for_crosswalks.cpp @@ -0,0 +1,204 @@ +// 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 "lanelet2_map_validator/validators/crosswalk/regulatory_element_details_for_crosswalks.hpp" +#include "map_validation_tester.hpp" + +#include +#include + +class TestRegulatoryElementsDetailsForCrosswalks : public MapValidationTester +{ +private: +}; + +TEST_F(TestRegulatoryElementsDetailsForCrosswalks, ValidatorAvailability) // NOLINT for gtest +{ + std::string expected_validator_name = + lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator::name(); + + lanelet::validation::Strings validators = + lanelet::validation::availabeChecks(expected_validator_name); // cspell:disable-line + + const uint32_t expected_validator_num = 1; + EXPECT_EQ(expected_validator_num, validators.size()); + EXPECT_EQ(expected_validator_name, validators[0]); +} + +TEST_F(TestRegulatoryElementsDetailsForCrosswalks, MissingRefers) // NOLINT for gtest +{ + load_target_map("crosswalk/crosswalk_regulatory_element_without_refers.osm"); + + lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; + const auto & issues = checker(*map_); + + EXPECT_EQ(issues.size(), 1); + EXPECT_EQ(issues[0].id, 31); + EXPECT_EQ(issues[0].severity, lanelet::validation::Severity::Error); + EXPECT_EQ(issues[0].primitive, lanelet::validation::Primitive::RegulatoryElement); + EXPECT_EQ( + issues[0].message, + "[Crosswalk.RegulatoryElementDetails-001] Regulatory element of crosswalk must have " + "lanelet of crosswalk(refers)."); +} + +TEST_F(TestRegulatoryElementsDetailsForCrosswalks, MultipleRefers) // NOLINT for gtest +{ + load_target_map("crosswalk/crosswalk_regulatory_element_with_multiple_refers.osm"); + + lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; + const auto & issues = checker(*map_); + + EXPECT_EQ(issues.size(), 1); + EXPECT_EQ(issues[0].id, 31); + EXPECT_EQ(issues[0].severity, lanelet::validation::Severity::Error); + EXPECT_EQ(issues[0].primitive, lanelet::validation::Primitive::RegulatoryElement); + EXPECT_EQ( + issues[0].message, + "[Crosswalk.RegulatoryElementDetails-002] Regulatory element of crosswalk must have " + "only one lanelet of crosswalk(refers)."); +} + +TEST_F(TestRegulatoryElementsDetailsForCrosswalks, MissingRefLine) // NOLINT for gtest +{ + load_target_map("crosswalk/crosswalk_without_stop_line.osm"); + + lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; + const auto & issues = checker(*map_); + + EXPECT_EQ(issues.size(), 1); + EXPECT_EQ(issues[0].id, 31); + EXPECT_EQ(issues[0].severity, lanelet::validation::Severity::Info); + EXPECT_EQ(issues[0].primitive, lanelet::validation::Primitive::RegulatoryElement); + EXPECT_EQ( + issues[0].message, + "[Crosswalk.RegulatoryElementDetails-003] Regulatory element of crosswalk does not " + "have stop line(ref_line)."); +} + +TEST_F(TestRegulatoryElementsDetailsForCrosswalks, MissingPolygon) // NOLINT for gtest +{ + load_target_map("crosswalk/crosswalk_without_polygon.osm"); + + lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; + const auto & issues = checker(*map_); + + EXPECT_EQ(issues.size(), 1); + EXPECT_EQ(issues[0].id, 31); + EXPECT_EQ(issues[0].severity, lanelet::validation::Severity::Warning); + EXPECT_EQ(issues[0].primitive, lanelet::validation::Primitive::RegulatoryElement); + EXPECT_EQ( + issues[0].message, + "[Crosswalk.RegulatoryElementDetails-004] Regulatory element of crosswalk is nice to " + "have crosswalk_polygon."); +} + +TEST_F(TestRegulatoryElementsDetailsForCrosswalks, MultiplePolygon) // NOLINT for gtest +{ + load_target_map("crosswalk/crosswalk_with_multiple_polygons.osm"); + + lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; + const auto & issues = checker(*map_); + + EXPECT_EQ(issues.size(), 1); + EXPECT_EQ(issues[0].id, 31); + EXPECT_EQ(issues[0].severity, lanelet::validation::Severity::Error); + EXPECT_EQ(issues[0].primitive, lanelet::validation::Primitive::RegulatoryElement); + EXPECT_EQ( + issues[0].message, + "[Crosswalk.RegulatoryElementDetails-005] Regulatory element of crosswalk must have " + "only one crosswalk_polygon."); +} + +TEST_F(TestRegulatoryElementsDetailsForCrosswalks, WrongRefersType) // NOLINT for gtest +{ + load_target_map("crosswalk/crosswalk_with_wrong_refers_type.osm"); + + lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; + const auto & issues = checker(*map_); + + EXPECT_EQ(issues.size(), 1); + EXPECT_EQ(issues[0].id, 18); + EXPECT_EQ(issues[0].severity, lanelet::validation::Severity::Error); + EXPECT_EQ(issues[0].primitive, lanelet::validation::Primitive::Lanelet); + EXPECT_EQ( + issues[0].message, + "[Crosswalk.RegulatoryElementDetails-006] Refers of crosswalk regulatory element must " + "have type of crosswalk."); +} + +TEST_F(TestRegulatoryElementsDetailsForCrosswalks, WrongRefLineType) // NOLINT for gtest +{ + load_target_map("crosswalk/crosswalk_with_wrong_ref_line_type.osm"); + + lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; + const auto & issues = checker(*map_); + + EXPECT_EQ(issues.size(), 1); + EXPECT_EQ(issues[0].id, 27); + EXPECT_EQ(issues[0].severity, lanelet::validation::Severity::Error); + EXPECT_EQ(issues[0].primitive, lanelet::validation::Primitive::LineString); + EXPECT_EQ( + issues[0].message, + "[Crosswalk.RegulatoryElementDetails-007] ref_line of crosswalk regulatory element " + "must have type of stopline."); +} + +TEST_F(TestRegulatoryElementsDetailsForCrosswalks, WrongPolygonType) // NOLINT for gtest +{ + load_target_map("crosswalk/crosswalk_with_wrong_polygon_type.osm"); + + lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; + const auto & issues = checker(*map_); + + EXPECT_EQ(issues.size(), 1); + EXPECT_EQ(issues[0].id, 24); + EXPECT_EQ(issues[0].severity, lanelet::validation::Severity::Error); + EXPECT_EQ(issues[0].primitive, lanelet::validation::Primitive::Polygon); + EXPECT_EQ( + issues[0].message, + "[Crosswalk.RegulatoryElementDetails-008] Crosswalk polygon of crosswalk regulatory " + "element must have type of crosswalk_polygon."); +} + +TEST_F(TestRegulatoryElementsDetailsForCrosswalks, CorrectDetails) // NOLINT for gtest +{ + load_target_map("crosswalk/crosswalk_with_regulatory_element.osm"); + + lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; + const auto & issues = checker(*map_); + + EXPECT_EQ(issues.size(), 0); +} + +TEST_F(TestRegulatoryElementsDetailsForCrosswalks, SampleMap) // NOLINT for gtest +{ + load_target_map("sample_map.osm"); + + lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; + const auto & issues = checker(*map_); + + uint64_t errors_and_warnings_count = 0; + + for (const auto & issue : issues) { + if ( + issue.severity == lanelet::validation::Severity::Error || + issue.severity == lanelet::validation::Severity::Warning) { + errors_and_warnings_count++; + } + } + + EXPECT_EQ(errors_and_warnings_count, 0); + EXPECT_EQ(issues.size(), 4); // Four INFOs should appear +} diff --git a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_elements_details_for_traffic_lights.cpp b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_elements_details_for_traffic_lights.cpp new file mode 100644 index 00000000..046f063c --- /dev/null +++ b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_elements_details_for_traffic_lights.cpp @@ -0,0 +1,131 @@ +// 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 "lanelet2_map_validator/validators/traffic_light/regulatory_element_details_for_traffic_lights.hpp" +#include "map_validation_tester.hpp" + +#include +#include + +class TestRegulatoryElementDetailsForTrafficLights : public MapValidationTester +{ +private: +}; + +TEST_F(TestRegulatoryElementDetailsForTrafficLights, ValidatorAvailability) // NOLINT for gtest +{ + std::string expected_validator_name = + lanelet::autoware::validation::RegulatoryElementsDetailsForTrafficLightsValidator::name(); + + lanelet::validation::Strings validators = + lanelet::validation::availabeChecks(expected_validator_name); // cspell:disable-line + + const uint32_t expected_validator_num = 1; + EXPECT_EQ(expected_validator_num, validators.size()); + EXPECT_EQ(expected_validator_name, validators[0]); +} + +TEST_F(TestRegulatoryElementDetailsForTrafficLights, MissingRefers) // NOLINT for gtest +{ + load_target_map("traffic_light/traffic_light_regulatory_element_without_refers.osm"); + + // traffic_light-type regulatory elements that has no refers will not be loaded from the start + // and should be mentioned in the loading_errors + + bool found_error_on_loading = false; + int target_primitive_id = 1025; + std::string target_message = + "Error parsing primitive " + std::to_string(target_primitive_id) + + ": Creating a regulatory element of type traffic_light failed: No traffic light defined!"; + + for (const auto & error : loading_errors_) { + if (error.find(target_message) != std::string::npos) { + found_error_on_loading = true; + break; + } + } + + EXPECT_TRUE(found_error_on_loading); +} + +TEST_F(TestRegulatoryElementDetailsForTrafficLights, MissingRefLine) // NOLINT for gtest +{ + load_target_map("traffic_light/traffic_light_regulatory_element_without_ref_line.osm"); + + lanelet::autoware::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker; + const auto & issues = checker(*map_); + + EXPECT_EQ(issues.size(), 1); + EXPECT_EQ(issues[0].id, 1025); + EXPECT_EQ(issues[0].severity, lanelet::validation::Severity::Error); + EXPECT_EQ(issues[0].primitive, lanelet::validation::Primitive::RegulatoryElement); + EXPECT_EQ( + issues[0].message, + "[TrafficLight.RegulatoryElementDetails-001] Regulatory element of traffic light must have a " + "stop line(ref_line)."); +} + +TEST_F(TestRegulatoryElementDetailsForTrafficLights, WrongRefersType) // NOLINT for gtest +{ + load_target_map("traffic_light/traffic_light_with_wrong_refers_type.osm"); + + lanelet::autoware::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker; + const auto & issues = checker(*map_); + + EXPECT_EQ(issues.size(), 1); + EXPECT_EQ(issues[0].id, 416); + EXPECT_EQ(issues[0].severity, lanelet::validation::Severity::Error); + EXPECT_EQ(issues[0].primitive, lanelet::validation::Primitive::LineString); + EXPECT_EQ( + issues[0].message, + "[TrafficLight.RegulatoryElementDetails-002] Refers of traffic light regulatory element must " + "have type of traffic_light."); +} + +TEST_F(TestRegulatoryElementDetailsForTrafficLights, WrongRefLineType) // NOLINT for gtest +{ + load_target_map("traffic_light/traffic_light_with_wrong_ref_line_type.osm"); + + lanelet::autoware::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker; + const auto & issues = checker(*map_); + + EXPECT_EQ(issues.size(), 1); + EXPECT_EQ(issues[0].id, 414); + EXPECT_EQ(issues[0].severity, lanelet::validation::Severity::Error); + EXPECT_EQ(issues[0].primitive, lanelet::validation::Primitive::LineString); + EXPECT_EQ( + issues[0].message, + "[TrafficLight.RegulatoryElementDetails-003] ref_line of traffic light regulatory element must " + "have type of stop_line."); +} + +TEST_F(TestRegulatoryElementDetailsForTrafficLights, CorrectDetails) // NOLINT for gtest +{ + load_target_map("traffic_light/traffic_light_with_regulatory_element.osm"); + + lanelet::autoware::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker; + const auto & issues = checker(*map_); + + EXPECT_EQ(issues.size(), 0); +} + +TEST_F(TestRegulatoryElementDetailsForTrafficLights, SampleMap) // NOLINT for gtest +{ + load_target_map("sample_map.osm"); + + lanelet::autoware::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker; + const auto & issues = checker(*map_); + + EXPECT_EQ(issues.size(), 0); +} diff --git a/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py b/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py index 8b32d0d0..a4202102 100755 --- a/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py +++ b/planning/planning_debug_tools/scripts/perception_replayer/perception_reproducer.py @@ -328,8 +328,7 @@ def add_perception_noise( ) args = parser.parse_args() - if not args.bag: - parser.error("The '--bag' argument is required.") + rclpy.init() if args.pub_route: pub_route(args.bag) diff --git a/planning/planning_debug_tools/scripts/perception_replayer/utils.py b/planning/planning_debug_tools/scripts/perception_replayer/utils.py index f1f628e3..0a1e6f53 100644 --- a/planning/planning_debug_tools/scripts/perception_replayer/utils.py +++ b/planning/planning_debug_tools/scripts/perception_replayer/utils.py @@ -207,8 +207,6 @@ def get_pose_from_bag(input_path: str, interval=(0.1, 10000.0)) -> Tuple[Pose, P def pub_route(input_path: str): - rclpy.init() - try: first_pose, last_pose = get_pose_from_bag(input_path) except Exception as e: diff --git a/system/rqt_diagnostic_graph_monitor/package.xml b/system/rqt_diagnostic_graph_monitor/package.xml index 60780e27..c0f42c38 100644 --- a/system/rqt_diagnostic_graph_monitor/package.xml +++ b/system/rqt_diagnostic_graph_monitor/package.xml @@ -10,9 +10,12 @@ ament_cmake_auto autoware_cmake + diagnostic_msgs python_qt_binding + rclpy rqt_gui rqt_gui_py + tier4_system_msgs ament_lint_auto autoware_lint_common