Skip to content

Commit

Permalink
Added autoware namespace to test codes
Browse files Browse the repository at this point in the history
Signed-off-by: TaikiYamada4 <[email protected]>
  • Loading branch information
TaikiYamada4 committed Nov 20, 2024
1 parent c1f94af commit 1504463
Show file tree
Hide file tree
Showing 5 changed files with 30 additions and 30 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ class TestMissingRegulatoryElementsForCrosswalks : public MapValidationTester
TEST_F(TestMissingRegulatoryElementsForCrosswalks, ValidatorAvailability) // NOLINT for gtest
{
std::string expected_validator_name =
lanelet::validation::MissingRegulatoryElementsForCrosswalksValidator::name();
lanelet::autoware::validation::MissingRegulatoryElementsForCrosswalksValidator::name();

lanelet::validation::Strings validators =
lanelet::validation::availabeChecks(expected_validator_name); // cspell:disable-line
Expand All @@ -40,7 +40,7 @@ TEST_F(TestMissingRegulatoryElementsForCrosswalks, MissingRegulatoryElement) //
{
load_target_map("crosswalk/crosswalk_without_regulatory_elements.osm");

lanelet::validation::MissingRegulatoryElementsForCrosswalksValidator checker;
lanelet::autoware::validation::MissingRegulatoryElementsForCrosswalksValidator checker;
const auto & issues = checker(*map_);

EXPECT_EQ(issues.size(), 1);
Expand All @@ -54,7 +54,7 @@ TEST_F(TestMissingRegulatoryElementsForCrosswalks, RegulatoryElementExists) //
{
load_target_map("crosswalk/crosswalk_with_regulatory_element.osm");

lanelet::validation::MissingRegulatoryElementsForCrosswalksValidator checker;
lanelet::autoware::validation::MissingRegulatoryElementsForCrosswalksValidator checker;
const auto & issues = checker(*map_);

EXPECT_EQ(issues.size(), 0);
Expand All @@ -64,7 +64,7 @@ TEST_F(TestMissingRegulatoryElementsForCrosswalks, SampleMap) // NOLINT for gte
{
load_target_map("sample_map.osm");

lanelet::validation::MissingRegulatoryElementsForCrosswalksValidator checker;
lanelet::autoware::validation::MissingRegulatoryElementsForCrosswalksValidator checker;
const auto & issues = checker(*map_);

EXPECT_EQ(issues.size(), 0);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ class TestMissingRegulatoryElementsForStopLines : public MapValidationTester
TEST_F(TestMissingRegulatoryElementsForStopLines, ValidatorAvailability) // NOLINT for gtest
{
std::string expected_validator_name =
lanelet::validation::MissingRegulatoryElementsForStopLinesValidator::name();
lanelet::autoware::validation::MissingRegulatoryElementsForStopLinesValidator::name();

lanelet::validation::Strings validators =
lanelet::validation::availabeChecks(expected_validator_name); // cspell:disable-line
Expand All @@ -40,7 +40,7 @@ TEST_F(TestMissingRegulatoryElementsForStopLines, MissingRegulatoryElement) //
{
load_target_map("stop_line/stop_line_without_regulatory_elements.osm");

lanelet::validation::MissingRegulatoryElementsForStopLinesValidator checker;
lanelet::autoware::validation::MissingRegulatoryElementsForStopLinesValidator checker;
const auto & issues = checker(*map_);

EXPECT_EQ(issues.size(), 1);
Expand All @@ -54,7 +54,7 @@ TEST_F(TestMissingRegulatoryElementsForStopLines, TrafficSignRegulatoryElement)
{
load_target_map("stop_line/stop_line_with_traffic_sign.osm");

lanelet::validation::MissingRegulatoryElementsForStopLinesValidator checker;
lanelet::autoware::validation::MissingRegulatoryElementsForStopLinesValidator checker;
const auto & issues = checker(*map_);

EXPECT_EQ(issues.size(), 0);
Expand All @@ -64,7 +64,7 @@ TEST_F(TestMissingRegulatoryElementsForStopLines, RoadMarkingRegulatoryElement)
{
load_target_map("stop_line/stop_line_with_road_marking.osm");

lanelet::validation::MissingRegulatoryElementsForStopLinesValidator checker;
lanelet::autoware::validation::MissingRegulatoryElementsForStopLinesValidator checker;
const auto & issues = checker(*map_);

EXPECT_EQ(issues.size(), 0);
Expand All @@ -74,7 +74,7 @@ TEST_F(TestMissingRegulatoryElementsForStopLines, SampleMap) // NOLINT for gtes
{
load_target_map("sample_map.osm");

lanelet::validation::MissingRegulatoryElementsForStopLinesValidator checker;
lanelet::autoware::validation::MissingRegulatoryElementsForStopLinesValidator checker;
const auto & issues = checker(*map_);

EXPECT_EQ(issues.size(), 0);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ class TestMissingRegulatoryElementsForTrafficLights : public MapValidationTester
TEST_F(TestMissingRegulatoryElementsForTrafficLights, ValidatorAvailability) // NOLINT for gtest
{
std::string expected_validator_name =
lanelet::validation::MissingRegulatoryElementsForTrafficLightsValidator::name();
lanelet::autoware::validation::MissingRegulatoryElementsForTrafficLightsValidator::name();

lanelet::validation::Strings validators =
lanelet::validation::availabeChecks(expected_validator_name); // cspell:disable-line
Expand All @@ -40,7 +40,7 @@ TEST_F(TestMissingRegulatoryElementsForTrafficLights, MissingRegulatoryElement)
{
load_target_map("traffic_light/traffic_light_without_regulatory_element.osm");

lanelet::validation::MissingRegulatoryElementsForTrafficLightsValidator checker;
lanelet::autoware::validation::MissingRegulatoryElementsForTrafficLightsValidator checker;
const auto & issues = checker(*map_);

EXPECT_EQ(issues.size(), 1);
Expand All @@ -54,7 +54,7 @@ TEST_F(TestMissingRegulatoryElementsForTrafficLights, RegulatoryElementExists)
{
load_target_map("traffic_light/traffic_light_with_regulatory_element.osm");

lanelet::validation::MissingRegulatoryElementsForTrafficLightsValidator checker;
lanelet::autoware::validation::MissingRegulatoryElementsForTrafficLightsValidator checker;
const auto & issues = checker(*map_);

EXPECT_EQ(issues.size(), 0);
Expand All @@ -64,7 +64,7 @@ TEST_F(TestMissingRegulatoryElementsForTrafficLights, SampleMap) // NOLINT for
{
load_target_map("sample_map.osm");

lanelet::validation::MissingRegulatoryElementsForTrafficLightsValidator checker;
lanelet::autoware::validation::MissingRegulatoryElementsForTrafficLightsValidator checker;
const auto & issues = checker(*map_);

EXPECT_EQ(issues.size(), 0);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ class TestRegulatoryElementsDetailsForCrosswalks : public MapValidationTester
TEST_F(TestRegulatoryElementsDetailsForCrosswalks, ValidatorAvailability) // NOLINT for gtest
{
std::string expected_validator_name =
lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator::name();
lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator::name();

lanelet::validation::Strings validators =
lanelet::validation::availabeChecks(expected_validator_name); // cspell:disable-line
Expand All @@ -40,7 +40,7 @@ TEST_F(TestRegulatoryElementsDetailsForCrosswalks, WrongRefersType) // NOLINT f
{
load_target_map("crosswalk/crosswalk_with_wrong_refers_type.osm");

lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker;
lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator checker;
const auto & issues = checker(*map_);

EXPECT_EQ(issues.size(), 1);
Expand All @@ -55,7 +55,7 @@ TEST_F(TestRegulatoryElementsDetailsForCrosswalks, WrongRefLineType) // NOLINT
{
load_target_map("crosswalk/crosswalk_with_wrong_ref_line_type.osm");

lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker;
lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator checker;
const auto & issues = checker(*map_);

EXPECT_EQ(issues.size(), 1);
Expand All @@ -70,7 +70,7 @@ TEST_F(TestRegulatoryElementsDetailsForCrosswalks, WrongPolygonType) // NOLINT
{
load_target_map("crosswalk/crosswalk_with_wrong_polygon_type.osm");

lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker;
lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator checker;
const auto & issues = checker(*map_);

EXPECT_EQ(issues.size(), 1);
Expand All @@ -86,7 +86,7 @@ TEST_F(TestRegulatoryElementsDetailsForCrosswalks, MissingPolygon) // NOLINT fo
{
load_target_map("crosswalk/crosswalk_without_polygon.osm");

lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker;
lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator checker;
const auto & issues = checker(*map_);

EXPECT_EQ(issues.size(), 1);
Expand All @@ -101,7 +101,7 @@ TEST_F(TestRegulatoryElementsDetailsForCrosswalks, MultiplePolygon) // NOLINT f
{
load_target_map("crosswalk/crosswalk_with_multiple_polygons.osm");

lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker;
lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator checker;
const auto & issues = checker(*map_);

EXPECT_EQ(issues.size(), 1);
Expand All @@ -116,7 +116,7 @@ TEST_F(TestRegulatoryElementsDetailsForCrosswalks, MissingRefLine) // NOLINT fo
{
load_target_map("crosswalk/crosswalk_without_stop_line.osm");

lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker;
lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator checker;
const auto & issues = checker(*map_);

EXPECT_EQ(issues.size(), 1);
Expand All @@ -131,7 +131,7 @@ TEST_F(TestRegulatoryElementsDetailsForCrosswalks, MissingRefers) // NOLINT for
{
load_target_map("crosswalk/crosswalk_regulatory_element_without_refers.osm");

lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker;
lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator checker;
const auto & issues = checker(*map_);

EXPECT_EQ(issues.size(), 1);
Expand All @@ -146,7 +146,7 @@ TEST_F(TestRegulatoryElementsDetailsForCrosswalks, MultipleRefers) // NOLINT fo
{
load_target_map("crosswalk/crosswalk_regulatory_element_with_multiple_refers.osm");

lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker;
lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator checker;
const auto & issues = checker(*map_);

EXPECT_EQ(issues.size(), 1);
Expand All @@ -162,7 +162,7 @@ TEST_F(TestRegulatoryElementsDetailsForCrosswalks, CorrectDetails) // NOLINT fo
{
load_target_map("crosswalk/crosswalk_with_regulatory_element.osm");

lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker;
lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator checker;
const auto & issues = checker(*map_);

EXPECT_EQ(issues.size(), 0);
Expand All @@ -172,7 +172,7 @@ TEST_F(TestRegulatoryElementsDetailsForCrosswalks, SampleMap) // NOLINT for gte
{
load_target_map("sample_map.osm");

lanelet::validation::RegulatoryElementsDetailsForCrosswalksValidator checker;
lanelet::autoware::validation::RegulatoryElementsDetailsForCrosswalksValidator checker;
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 @@ -26,7 +26,7 @@ class TestRegulatoryElementDetailsForTrafficLights : public MapValidationTester
TEST_F(TestRegulatoryElementDetailsForTrafficLights, ValidatorAvailability) // NOLINT for gtest
{
std::string expected_validator_name =
lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator::name();
lanelet::autoware::validation::RegulatoryElementsDetailsForTrafficLightsValidator::name();

lanelet::validation::Strings validators =
lanelet::validation::availabeChecks(expected_validator_name); // cspell:disable-line
Expand All @@ -40,7 +40,7 @@ TEST_F(TestRegulatoryElementDetailsForTrafficLights, WrongRefersType) // NOLINT
{
load_target_map("traffic_light/traffic_light_with_wrong_refers_type.osm");

lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker;
lanelet::autoware::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker;
const auto & issues = checker(*map_);

EXPECT_EQ(issues.size(), 1);
Expand All @@ -56,7 +56,7 @@ TEST_F(TestRegulatoryElementDetailsForTrafficLights, WrongRefLineType) // NOLIN
{
load_target_map("traffic_light/traffic_light_with_wrong_ref_line_type.osm");

lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker;
lanelet::autoware::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker;
const auto & issues = checker(*map_);

EXPECT_EQ(issues.size(), 1);
Expand Down Expand Up @@ -94,7 +94,7 @@ TEST_F(TestRegulatoryElementDetailsForTrafficLights, MissingRefLine) // NOLINT
{
load_target_map("traffic_light/traffic_light_regulatory_element_without_ref_line.osm");

lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker;
lanelet::autoware::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker;
const auto & issues = checker(*map_);

EXPECT_EQ(issues.size(), 1);
Expand All @@ -109,7 +109,7 @@ TEST_F(TestRegulatoryElementDetailsForTrafficLights, CorrectDetails) // NOLINT
{
load_target_map("traffic_light/traffic_light_with_regulatory_element.osm");

lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker;
lanelet::autoware::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker;
const auto & issues = checker(*map_);

EXPECT_EQ(issues.size(), 0);
Expand All @@ -119,7 +119,7 @@ TEST_F(TestRegulatoryElementDetailsForTrafficLights, SampleMap) // NOLINT for g
{
load_target_map("sample_map.osm");

lanelet::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker;
lanelet::autoware::validation::RegulatoryElementsDetailsForTrafficLightsValidator checker;
const auto & issues = checker(*map_);

EXPECT_EQ(issues.size(), 0);
Expand Down

0 comments on commit 1504463

Please sign in to comment.