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 186a563f..bd98f3ce 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 @@ -63,35 +63,6 @@ RegulatoryElementsDetailsForCrosswalksValidator::checkRegulatoryElementOfCrosswa auto crosswalk_polygons = elem->getParameters( lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon); - // If this is a crosswalk type regulatory element, the "refers" has to be a "crosswalk" subtype - // lanelet - const auto & issue_cw = lanelet::validation::Issue( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::Lanelet, - lanelet::utils::getId(), - "Refers of crosswalk regulatory element must have type of crosswalk."); - lanelet::autoware::validation::checkPrimitivesType( - refers, lanelet::AttributeValueString::Lanelet, lanelet::AttributeValueString::Crosswalk, - issue_cw, issues); - - // If this is a crosswalk type regulatory element, the "ref_line" has to be a "stop_line" type - // linestring - const auto & issue_sl = lanelet::validation::Issue( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, - lanelet::utils::getId(), - "ref_line of crosswalk regulatory element must have type of stopline."); - lanelet::autoware::validation::checkPrimitivesType( - ref_lines, lanelet::AttributeValueString::StopLine, issue_sl, issues); - - // If this is a crosswalk type regulatory element, the "crosswalk_polygon" has to be a - // "crosswalk_polygon" type polygon - const auto & issue_poly = lanelet::validation::Issue( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::Polygon, - lanelet::utils::getId(), - "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon."); - lanelet::autoware::validation::checkPrimitivesType( - crosswalk_polygons, lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon, - issue_poly, issues); - // Report warning if regulatory element does not have crosswalk polygon if (crosswalk_polygons.empty()) { issues.emplace_back( @@ -121,6 +92,35 @@ RegulatoryElementsDetailsForCrosswalksValidator::checkRegulatoryElementOfCrosswa elem->id(), "Regulatory element of crosswalk must have only one lanelet of crosswalk(refers)."); } + + // If this is a crosswalk type regulatory element, the "refers" has to be a "crosswalk" subtype + // lanelet + const auto & issue_cw = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::Lanelet, + lanelet::utils::getId(), + "Refers of crosswalk regulatory element must have type of crosswalk."); + lanelet::autoware::validation::checkPrimitivesType( + refers, lanelet::AttributeValueString::Lanelet, lanelet::AttributeValueString::Crosswalk, + issue_cw, issues); + + // If this is a crosswalk type regulatory element, the "ref_line" has to be a "stop_line" type + // linestring + const auto & issue_sl = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, + lanelet::utils::getId(), + "ref_line of crosswalk regulatory element must have type of stopline."); + lanelet::autoware::validation::checkPrimitivesType( + ref_lines, lanelet::AttributeValueString::StopLine, issue_sl, issues); + + // If this is a crosswalk type regulatory element, the "crosswalk_polygon" has to be a + // "crosswalk_polygon" type polygon + const auto & issue_poly = lanelet::validation::Issue( + lanelet::validation::Severity::Error, lanelet::validation::Primitive::Polygon, + lanelet::utils::getId(), + "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon."); + lanelet::autoware::validation::checkPrimitivesType( + crosswalk_polygons, lanelet::autoware::Crosswalk::AutowareRoleNameString::CrosswalkPolygon, + issue_poly, issues); } return issues; } 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 2ea53fa2..ff9f4535 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 @@ -72,19 +72,6 @@ RegulatoryElementsDetailsForTrafficLightsValidator::checkRegulatoryElementOfTraf auto refers = elem->getParameters(lanelet::RoleName::Refers); // Get stop line referred by regulatory element auto ref_lines = elem->getParameters(lanelet::RoleName::RefLine); - const auto & issue_tl = lanelet::validation::Issue( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, - lanelet::utils::getId(), - "Refers of traffic light regulatory element must have type of traffic_light."); - lanelet::autoware::validation::checkPrimitivesType( - refers, lanelet::AttributeValueString::TrafficLight, issue_tl, issues); - - const auto & issue_sl = lanelet::validation::Issue( - lanelet::validation::Severity::Error, lanelet::validation::Primitive::LineString, - lanelet::utils::getId(), - "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); if (refers.empty()) { issues.emplace_back( @@ -106,6 +93,20 @@ RegulatoryElementsDetailsForTrafficLightsValidator::checkRegulatoryElementOfTraf lanelet::validation::Severity::Error, lanelet::validation::Primitive::RegulatoryElement, elem->id(), "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."); + 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."); + lanelet::autoware::validation::checkPrimitivesType( + ref_lines, lanelet::AttributeValueString::StopLine, issue_sl, issues); } return issues; } diff --git a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp index 191884b1..6241c8c7 100644 --- a/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp +++ b/map/autoware_lanelet2_map_validator/test/src/test_regulatory_element_details.cpp @@ -185,23 +185,15 @@ TEST_F(TestSuite, RegulatoryElementOfTrafficLightWithoutTrafficLight) // NOLINT lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker; const auto & issues = checker(*test_map_ptr); - uint8_t expected_num_issues = 2; + uint8_t expected_num_issues = 1; static constexpr const char * expected_message1 = "Refers of traffic light regulatory element must have type of traffic_light."; - static constexpr const char * expected_message2 = - "Regulatory element of traffic light must have a traffic light(refers)."; EXPECT_EQ(expected_num_issues, issues.size()); for (const auto & issue : issues) { if (issue.id == 99998) { EXPECT_EQ(expected_message1, issue.message); EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); EXPECT_EQ(lanelet::validation::Primitive::LineString, issue.primitive); - } else if (issue.id == 99999) { - EXPECT_EQ(expected_message2, issue.message); - EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); - EXPECT_EQ(lanelet::validation::Primitive::RegulatoryElement, issue.primitive); - } else { - FAIL() << "Unexpected issue id: " << issue.id; } } } @@ -225,23 +217,15 @@ TEST_F(TestSuite, RegulatoryElementOfTrafficLightWithoutStopLine) // NOLINT for lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker; const auto & issues = checker(*test_map_ptr); - uint8_t expected_num_issues = 2; + 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."; - static constexpr const char * expected_message2 = - "Regulatory element of traffic light must have a stop line(ref_line)."; EXPECT_EQ(expected_num_issues, issues.size()); for (const auto & issue : issues) { if (issue.id == 99998) { EXPECT_EQ(expected_message1, issue.message); EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); EXPECT_EQ(lanelet::validation::Primitive::LineString, issue.primitive); - } else if (issue.id == 99999) { - EXPECT_EQ(expected_message2, issue.message); - EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); - EXPECT_EQ(lanelet::validation::Primitive::RegulatoryElement, issue.primitive); - } else { - FAIL() << "Unexpected issue id: " << issue.id; } } } @@ -270,23 +254,15 @@ TEST_F(TestSuite, RegulatoryElementOfCrosswalkWithoutPolygon) // NOLINT for gte lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; const auto & issues = checker(*test_map_ptr); - uint8_t expected_num_issues = 2; + uint8_t expected_num_issues = 1; static constexpr const char * expected_message1 = "Crosswalk polygon of crosswalk regulatory element must have type of Crosswalk_polygon."; - static constexpr const char * expected_message2 = - "Regulatory element of crosswalk is nice to have crosswalk_polygon."; EXPECT_EQ(expected_num_issues, issues.size()); for (const auto & issue : issues) { if (issue.id == 99998) { EXPECT_EQ(expected_message1, issue.message); EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); EXPECT_EQ(lanelet::validation::Primitive::Polygon, issue.primitive); - } else if (issue.id == 99999) { - EXPECT_EQ(expected_message2, issue.message); - EXPECT_EQ(lanelet::validation::Severity::Warning, issue.severity); - EXPECT_EQ(lanelet::validation::Primitive::RegulatoryElement, issue.primitive); - } else { - FAIL() << "Unexpected issue id: " << issue.id; } } } @@ -346,23 +322,15 @@ TEST_F(TestSuite, RegulatoryElementOfCrosswalkWithoutCrosswalk) // NOLINT for g lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker; const auto & issues = checker(*test_map_ptr); - uint8_t expected_num_issues = 2; + uint8_t expected_num_issues = 1; static constexpr const char * expected_message1 = "Refers of crosswalk regulatory element must have type of crosswalk."; - static constexpr const char * expected_message2 = - "Regulatory element of crosswalk must have lanelet of crosswalk(refers)."; EXPECT_EQ(expected_num_issues, issues.size()); for (const auto & issue : issues) { if (issue.id == 99998) { EXPECT_EQ(expected_message1, issue.message); EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); EXPECT_EQ(lanelet::validation::Primitive::Lanelet, issue.primitive); - } else if (issue.id == 99999) { - EXPECT_EQ(expected_message2, issue.message); - EXPECT_EQ(lanelet::validation::Severity::Error, issue.severity); - EXPECT_EQ(lanelet::validation::Primitive::RegulatoryElement, issue.primitive); - } else { - FAIL() << "Unexpected issue id: " << issue.id; } } }