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..f6997634 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 @@ -16,7 +16,7 @@ The output issue marks "lanelet", "linestring" or "regulatory_element" as the ** | ---------------------------------------------------------------------------------------- | -------- | ------------------ | ---------------------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | | "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. | +| "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. | 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 bd98f3ce..70b36acc 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 @@ -117,7 +117,7 @@ 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."); + "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/test/src/map_validation_tester.hpp b/map/autoware_lanelet2_map_validator/test/src/map_validation_tester.hpp index ac5cff16..6fc142dd 100644 --- a/map/autoware_lanelet2_map_validator/test/src/map_validation_tester.hpp +++ b/map/autoware_lanelet2_map_validator/test/src/map_validation_tester.hpp @@ -35,14 +35,14 @@ class MapValidationTester : public ::testing::Test 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); + map_ = lanelet::load( + package_share_directory + "/data/map/" + file_name, *projector, &loading_errors_); - EXPECT_NE(map, nullptr); + EXPECT_NE(map_, nullptr); } - lanelet::LaneletMapPtr map{nullptr}; - std::vector loading_errors; + lanelet::LaneletMapPtr map_{nullptr}; + std::vector loading_errors_; }; #endif // MAP_VALIDATION_TESTER_HPP_ 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 index 8731ca6f..2e48df3b 100644 --- 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 @@ -41,7 +41,7 @@ TEST_F(TestMissingRegulatoryElementsForCrosswalks, MissingRegulatoryElement) // load_target_map("crosswalk/crosswalk_without_regulatory_elements.osm"); lanelet::validation::MissingRegulatoryElementsForCrosswalksValidator checker; - const auto & issues = checker(*map); + const auto & issues = checker(*map_); EXPECT_EQ(issues.size(), 1); EXPECT_EQ(issues[0].id, 18); @@ -55,7 +55,7 @@ TEST_F(TestMissingRegulatoryElementsForCrosswalks, RegulatoryElementExists) // load_target_map("crosswalk/crosswalk_with_regulatory_element.osm"); lanelet::validation::MissingRegulatoryElementsForCrosswalksValidator checker; - const auto & issues = checker(*map); + const auto & issues = checker(*map_); EXPECT_EQ(issues.size(), 0); } @@ -65,7 +65,7 @@ TEST_F(TestMissingRegulatoryElementsForCrosswalks, SampleMap) // NOLINT for gte load_target_map("sample_map.osm"); lanelet::validation::MissingRegulatoryElementsForCrosswalksValidator checker; - const auto & issues = checker(*map); + 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 index 24fd733e..d073f3b7 100644 --- 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 @@ -41,7 +41,7 @@ TEST_F(TestMissingRegulatoryElementsForStopLines, MissingRegulatoryElement) // load_target_map("stop_line/stop_line_without_regulatory_elements.osm"); lanelet::validation::MissingRegulatoryElementsForStopLinesValidator checker; - const auto & issues = checker(*map); + const auto & issues = checker(*map_); EXPECT_EQ(issues.size(), 1); EXPECT_EQ(issues[0].id, 2156); @@ -55,7 +55,7 @@ TEST_F(TestMissingRegulatoryElementsForStopLines, TrafficSignRegulatoryElement) load_target_map("stop_line/stop_line_with_traffic_sign.osm"); lanelet::validation::MissingRegulatoryElementsForStopLinesValidator checker; - const auto & issues = checker(*map); + const auto & issues = checker(*map_); EXPECT_EQ(issues.size(), 0); } @@ -65,7 +65,7 @@ TEST_F(TestMissingRegulatoryElementsForStopLines, RoadMarkingRegulatoryElement) load_target_map("stop_line/stop_line_with_road_marking.osm"); lanelet::validation::MissingRegulatoryElementsForStopLinesValidator checker; - const auto & issues = checker(*map); + const auto & issues = checker(*map_); EXPECT_EQ(issues.size(), 0); } @@ -75,7 +75,7 @@ TEST_F(TestMissingRegulatoryElementsForStopLines, SampleMap) // NOLINT for gtes load_target_map("sample_map.osm"); lanelet::validation::MissingRegulatoryElementsForStopLinesValidator checker; - const auto & issues = checker(*map); + 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 index edabdb28..e5bfec89 100644 --- 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 @@ -41,7 +41,7 @@ TEST_F(TestMissingRegulatoryElementsForTrafficLights, MissingRegulatoryElement) load_target_map("traffic_light/traffic_light_without_regulatory_element.osm"); lanelet::validation::MissingRegulatoryElementsForTrafficLightsValidator checker; - const auto & issues = checker(*map); + const auto & issues = checker(*map_); EXPECT_EQ(issues.size(), 1); EXPECT_EQ(issues[0].id, 416); @@ -55,7 +55,7 @@ TEST_F(TestMissingRegulatoryElementsForTrafficLights, RegulatoryElementExists) load_target_map("traffic_light/traffic_light_with_regulatory_element.osm"); lanelet::validation::MissingRegulatoryElementsForTrafficLightsValidator checker; - const auto & issues = checker(*map); + const auto & issues = checker(*map_); EXPECT_EQ(issues.size(), 0); } @@ -65,7 +65,7 @@ TEST_F(TestMissingRegulatoryElementsForTrafficLights, SampleMap) // NOLINT for load_target_map("sample_map.osm"); lanelet::validation::MissingRegulatoryElementsForTrafficLightsValidator checker; - const auto & issues = checker(*map); + const auto & issues = checker(*map_); EXPECT_EQ(issues.size(), 0); } 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 index a08c3155..da779142 100644 --- 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 @@ -41,7 +41,7 @@ TEST_F(TestRegulatoryElementsDetailsForCrosswalks, WrongRefersType) // NOLINT f load_target_map("crosswalk/crosswalk_with_wrong_refers_type.osm"); lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; - const auto & issues = checker(*map); + const auto & issues = checker(*map_); EXPECT_EQ(issues.size(), 1); EXPECT_EQ(issues[0].id, 18); @@ -56,7 +56,7 @@ TEST_F(TestRegulatoryElementsDetailsForCrosswalks, WrongRefLineType) // NOLINT load_target_map("crosswalk/crosswalk_with_wrong_ref_line_type.osm"); lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; - const auto & issues = checker(*map); + const auto & issues = checker(*map_); EXPECT_EQ(issues.size(), 1); EXPECT_EQ(issues[0].id, 27); @@ -71,7 +71,7 @@ TEST_F(TestRegulatoryElementsDetailsForCrosswalks, WrongPolygonType) // NOLINT load_target_map("crosswalk/crosswalk_with_wrong_polygon_type.osm"); lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; - const auto & issues = checker(*map); + const auto & issues = checker(*map_); EXPECT_EQ(issues.size(), 1); EXPECT_EQ(issues[0].id, 24); @@ -79,7 +79,7 @@ TEST_F(TestRegulatoryElementsDetailsForCrosswalks, WrongPolygonType) // NOLINT EXPECT_EQ(issues[0].primitive, lanelet::validation::Primitive::Polygon); EXPECT_EQ( issues[0].message, - "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon."); + "Crosswalk polygon of crosswalk regulatory element must have type of crosswalk_polygon."); } TEST_F(TestRegulatoryElementsDetailsForCrosswalks, MissingPolygon) // NOLINT for gtest @@ -87,7 +87,7 @@ TEST_F(TestRegulatoryElementsDetailsForCrosswalks, MissingPolygon) // NOLINT fo load_target_map("crosswalk/crosswalk_without_polygon.osm"); lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; - const auto & issues = checker(*map); + const auto & issues = checker(*map_); EXPECT_EQ(issues.size(), 1); EXPECT_EQ(issues[0].id, 31); @@ -102,7 +102,7 @@ TEST_F(TestRegulatoryElementsDetailsForCrosswalks, MultiplePolygon) // NOLINT f load_target_map("crosswalk/crosswalk_with_multiple_polygons.osm"); lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; - const auto & issues = checker(*map); + const auto & issues = checker(*map_); EXPECT_EQ(issues.size(), 1); EXPECT_EQ(issues[0].id, 31); @@ -117,7 +117,7 @@ TEST_F(TestRegulatoryElementsDetailsForCrosswalks, MissingRefLine) // NOLINT fo load_target_map("crosswalk/crosswalk_without_stop_line.osm"); lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; - const auto & issues = checker(*map); + const auto & issues = checker(*map_); EXPECT_EQ(issues.size(), 1); EXPECT_EQ(issues[0].id, 31); @@ -132,7 +132,7 @@ TEST_F(TestRegulatoryElementsDetailsForCrosswalks, MissingRefers) // NOLINT for load_target_map("crosswalk/crosswalk_regulatory_element_without_refers.osm"); lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; - const auto & issues = checker(*map); + const auto & issues = checker(*map_); EXPECT_EQ(issues.size(), 1); EXPECT_EQ(issues[0].id, 31); @@ -147,7 +147,7 @@ TEST_F(TestRegulatoryElementsDetailsForCrosswalks, MultipleRefers) // NOLINT fo load_target_map("crosswalk/crosswalk_regulatory_element_with_multiple_refers.osm"); lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; - const auto & issues = checker(*map); + const auto & issues = checker(*map_); EXPECT_EQ(issues.size(), 1); EXPECT_EQ(issues[0].id, 31); @@ -163,7 +163,7 @@ TEST_F(TestRegulatoryElementsDetailsForCrosswalks, CorrectDetails) // NOLINT fo load_target_map("crosswalk/crosswalk_with_regulatory_element.osm"); lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; - const auto & issues = checker(*map); + const auto & issues = checker(*map_); EXPECT_EQ(issues.size(), 0); } @@ -173,7 +173,7 @@ TEST_F(TestRegulatoryElementsDetailsForCrosswalks, SampleMap) // NOLINT for gte load_target_map("sample_map.osm"); lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; - const auto & issues = checker(*map); + const auto & issues = checker(*map_); uint64_t errors_and_warnings_count = 0; 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 index e0d239d9..8bd2b730 100644 --- 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 @@ -41,7 +41,7 @@ TEST_F(TestRegulatoryElementDetailsForTrafficLights, WrongRefersType) // NOLINT load_target_map("traffic_light/traffic_light_with_wrong_refers_type.osm"); lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker; - const auto & issues = checker(*map); + const auto & issues = checker(*map_); EXPECT_EQ(issues.size(), 1); EXPECT_EQ(issues[0].id, 416); @@ -57,7 +57,7 @@ TEST_F(TestRegulatoryElementDetailsForTrafficLights, WrongRefLineType) // NOLIN load_target_map("traffic_light/traffic_light_with_wrong_ref_line_type.osm"); lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker; - const auto & issues = checker(*map); + const auto & issues = checker(*map_); EXPECT_EQ(issues.size(), 1); EXPECT_EQ(issues[0].id, 414); @@ -80,7 +80,7 @@ TEST_F(TestRegulatoryElementDetailsForTrafficLights, MissingRefers) // NOLINT f "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) { + for (const auto & error : loading_errors_) { if (error.find(target_message) != std::string::npos) { found_error_on_loading = true; break; @@ -95,11 +95,7 @@ TEST_F(TestRegulatoryElementDetailsForTrafficLights, MissingRefLine) // NOLINT load_target_map("traffic_light/traffic_light_regulatory_element_without_ref_line.osm"); lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker; - const auto & issues = checker(*map); - - for (const auto & error : loading_errors) { - std::cout << error << std::endl; - } + const auto & issues = checker(*map_); EXPECT_EQ(issues.size(), 1); EXPECT_EQ(issues[0].id, 1025); @@ -114,7 +110,7 @@ TEST_F(TestRegulatoryElementDetailsForTrafficLights, CorrectDetails) // NOLINT load_target_map("traffic_light/traffic_light_with_regulatory_element.osm"); lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker; - const auto & issues = checker(*map); + const auto & issues = checker(*map_); EXPECT_EQ(issues.size(), 0); } @@ -124,7 +120,7 @@ TEST_F(TestRegulatoryElementDetailsForTrafficLights, SampleMap) // NOLINT for g load_target_map("sample_map.osm"); lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker; - const auto & issues = checker(*map); + const auto & issues = checker(*map_); EXPECT_EQ(issues.size(), 0); }