Skip to content

Commit

Permalink
Reflect PR comments
Browse files Browse the repository at this point in the history
Signed-off-by: TaikiYamada4 <[email protected]>
  • Loading branch information
TaikiYamada4 committed Nov 18, 2024
1 parent 6534914 commit 2b3cfe8
Show file tree
Hide file tree
Showing 8 changed files with 34 additions and 38 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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. |
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::string> loading_errors;
lanelet::LaneletMapPtr map_{nullptr};
std::vector<std::string> loading_errors_;
};

#endif // MAP_VALIDATION_TESTER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand All @@ -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);
}
Expand All @@ -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);
}
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand All @@ -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);
}
Expand All @@ -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);
}
Expand All @@ -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);
}
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand All @@ -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);
}
Expand All @@ -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);
}
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand All @@ -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);
Expand All @@ -71,23 +71,23 @@ 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);
EXPECT_EQ(issues[0].severity, lanelet::validation::Severity::Error);
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
{
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);
Expand All @@ -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);
Expand All @@ -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);
Expand All @@ -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);
Expand All @@ -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);
Expand All @@ -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);
}
Expand All @@ -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;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand All @@ -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);
Expand All @@ -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;
Expand All @@ -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);
Expand All @@ -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);
}
Expand All @@ -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);
}

0 comments on commit 2b3cfe8

Please sign in to comment.