From fc82d29fd533db5790dac15da50fbf8967474118 Mon Sep 17 00:00:00 2001 From: arundas <arun.das@bmw.de> Date: Wed, 27 Jul 2022 13:43:33 +0200 Subject: [PATCH] fix(opSimulation): Update mapper to use OpenDRIVE standard, fix syntax of error messasge Co-authored-by: Theresa Hefele <Theresa.Hefele@bmw.de> --- .../opSimulation/importer/sceneryImporter.cpp | 12 ++++++++ .../World_OSI/OWL/OpenDriveTypeMapper.h | 30 +++++++++---------- .../modules/World_OSI/OWL/TrafficLight.cpp | 17 ++++++----- .../ImporterTest/IntegrationTestScenery.xodr | 4 +-- .../modules/World_OSI/datatypes_Tests.cpp | 14 ++++----- .../opSimulation/sceneryImporter_Tests.cpp | 2 +- 6 files changed, 46 insertions(+), 33 deletions(-) diff --git a/sim/src/core/opSimulation/importer/sceneryImporter.cpp b/sim/src/core/opSimulation/importer/sceneryImporter.cpp index be7eb27c6..a65948c49 100644 --- a/sim/src/core/opSimulation/importer/sceneryImporter.cpp +++ b/sim/src/core/opSimulation/importer/sceneryImporter.cpp @@ -683,6 +683,18 @@ void SceneryImporter::ParseSignals(QDomElement& roadElement, signalElement, "Attribute " + std::string(ATTRIBUTE::type) + " is missing."); ThrowIfFalse(ParseAttributeString(signalElement, ATTRIBUTE::subtype, signal.subtype), signalElement, "Attribute " + std::string(ATTRIBUTE::subtype) + " is missing."); + + //OpenDRIVE 1.6 standard defines subtypes to be "-1". Maps until now use subtype = "". + if (signal.subtype == "" || signal.subtype == " "){ + LOG_INTERN(LogLevel::Warning) << "Encountered signal with empty subtype definition. That is not supported in openDRIVE 1.6 -> interpreting empty subtype as \"-1\""; + signal.subtype = "-1"; + + } else if (signal.subtype == "none"){ + LOG_INTERN(LogLevel::Warning) << "Encountered signal with typedefinition \"none\". Translated that to \"-1\""; + signal.subtype = "-1"; + } + + // optional std::string signalUnit; ParseAttributeDouble(signalElement, ATTRIBUTE::value, signal.value); diff --git a/sim/src/core/opSimulation/modules/World_OSI/OWL/OpenDriveTypeMapper.h b/sim/src/core/opSimulation/modules/World_OSI/OWL/OpenDriveTypeMapper.h index 6336f8488..5d04c8aa4 100644 --- a/sim/src/core/opSimulation/modules/World_OSI/OWL/OpenDriveTypeMapper.h +++ b/sim/src/core/opSimulation/modules/World_OSI/OWL/OpenDriveTypeMapper.h @@ -119,14 +119,14 @@ namespace OpenDriveTypeMapper { {"274.1", {osi3::TrafficSignValue_Unit::TrafficSignValue_Unit_UNIT_KILOMETER_PER_HOUR, { - {"", {30.0, osi3::TrafficSign_MainSign_Classification_Type::TrafficSign_MainSign_Classification_Type_TYPE_SPEED_LIMIT_ZONE_BEGIN}}, + {"-1", {30.0, osi3::TrafficSign_MainSign_Classification_Type::TrafficSign_MainSign_Classification_Type_TYPE_SPEED_LIMIT_ZONE_BEGIN}}, {"20", {20.0, osi3::TrafficSign_MainSign_Classification_Type::TrafficSign_MainSign_Classification_Type_TYPE_SPEED_LIMIT_ZONE_BEGIN}} } } }, {"274.2", {osi3::TrafficSignValue_Unit::TrafficSignValue_Unit_UNIT_KILOMETER_PER_HOUR, { - {"", {30.0, osi3::TrafficSign_MainSign_Classification_Type::TrafficSign_MainSign_Classification_Type_TYPE_SPEED_LIMIT_ZONE_END}}, + {"-1", {30.0, osi3::TrafficSign_MainSign_Classification_Type::TrafficSign_MainSign_Classification_Type_TYPE_SPEED_LIMIT_ZONE_END}}, {"20", {20.0, osi3::TrafficSign_MainSign_Classification_Type::TrafficSign_MainSign_Classification_Type_TYPE_SPEED_LIMIT_ZONE_END}} } } @@ -287,7 +287,7 @@ namespace OpenDriveTypeMapper { {"1.000.001", { - {"", osi3::TrafficLight_Classification_Icon::TrafficLight_Classification_Icon_ICON_NONE} + {"-1", osi3::TrafficLight_Classification_Icon::TrafficLight_Classification_Icon_ICON_NONE} } }, {"1.000.011", @@ -310,12 +310,12 @@ namespace OpenDriveTypeMapper { {"1.000.002", { - {"", osi3::TrafficLight_Classification_Icon::TrafficLight_Classification_Icon_ICON_PEDESTRIAN} + {"-1", osi3::TrafficLight_Classification_Icon::TrafficLight_Classification_Icon_ICON_PEDESTRIAN} } }, {"1.000.007", { - {"", osi3::TrafficLight_Classification_Icon::TrafficLight_Classification_Icon_ICON_PEDESTRIAN_AND_BICYCLE} + {"-1", osi3::TrafficLight_Classification_Icon::TrafficLight_Classification_Icon_ICON_PEDESTRIAN_AND_BICYCLE} } }, {"1.000.009", @@ -333,7 +333,7 @@ namespace OpenDriveTypeMapper }, {"1.000.013", { - {"", osi3::TrafficLight_Classification_Icon::TrafficLight_Classification_Icon_ICON_BICYCLE} + {"-1", osi3::TrafficLight_Classification_Icon::TrafficLight_Classification_Icon_ICON_BICYCLE} } }, }; @@ -342,13 +342,13 @@ namespace OpenDriveTypeMapper { {"1.000.002", { - {"", {osi3::TrafficLight_Classification_Color::TrafficLight_Classification_Color_COLOR_RED, + {"-1", {osi3::TrafficLight_Classification_Color::TrafficLight_Classification_Color_COLOR_RED, osi3::TrafficLight_Classification_Color::TrafficLight_Classification_Color_COLOR_GREEN}} } }, {"1.000.007", { - {"", {osi3::TrafficLight_Classification_Color::TrafficLight_Classification_Color_COLOR_RED, + {"-1", {osi3::TrafficLight_Classification_Color::TrafficLight_Classification_Color_COLOR_RED, osi3::TrafficLight_Classification_Color::TrafficLight_Classification_Color_COLOR_GREEN}} } }, @@ -375,7 +375,7 @@ namespace OpenDriveTypeMapper }, {"1.000.013", { - {"", {osi3::TrafficLight_Classification_Color::TrafficLight_Classification_Color_COLOR_RED, + {"-1", {osi3::TrafficLight_Classification_Color::TrafficLight_Classification_Color_COLOR_RED, osi3::TrafficLight_Classification_Color::TrafficLight_Classification_Color_COLOR_GREEN}} } }, @@ -398,7 +398,7 @@ namespace OpenDriveTypeMapper }, {"1.000.008", { - {"", {osi3::TrafficLight_Classification_Icon::TrafficLight_Classification_Icon_ICON_NONE}}, + {"-1", {osi3::TrafficLight_Classification_Icon::TrafficLight_Classification_Icon_ICON_NONE}}, {"10", {osi3::TrafficLight_Classification_Icon::TrafficLight_Classification_Icon_ICON_ARROW_LEFT}}, {"20", {osi3::TrafficLight_Classification_Icon::TrafficLight_Classification_Icon_ICON_ARROW_RIGHT}}, {"30", {osi3::TrafficLight_Classification_Icon::TrafficLight_Classification_Icon_ICON_ARROW_STRAIGHT_AHEAD}}, @@ -410,7 +410,7 @@ namespace OpenDriveTypeMapper }, {"1.000.012", { - {"", {osi3::TrafficLight_Classification_Icon::TrafficLight_Classification_Icon_ICON_NONE}}, + {"-1", {osi3::TrafficLight_Classification_Icon::TrafficLight_Classification_Icon_ICON_NONE}}, {"10", {osi3::TrafficLight_Classification_Icon::TrafficLight_Classification_Icon_ICON_ARROW_LEFT}}, {"20", {osi3::TrafficLight_Classification_Icon::TrafficLight_Classification_Icon_ICON_ARROW_RIGHT}}, {"30", {osi3::TrafficLight_Classification_Icon::TrafficLight_Classification_Icon_ICON_ARROW_STRAIGHT_AHEAD}}, @@ -422,7 +422,7 @@ namespace OpenDriveTypeMapper }, {"1.000.020", { - {"", {osi3::TrafficLight_Classification_Icon::TrafficLight_Classification_Icon_ICON_NONE}}, + {"-1", {osi3::TrafficLight_Classification_Icon::TrafficLight_Classification_Icon_ICON_NONE}}, {"10", {osi3::TrafficLight_Classification_Icon::TrafficLight_Classification_Icon_ICON_ARROW_LEFT}}, {"20", {osi3::TrafficLight_Classification_Icon::TrafficLight_Classification_Icon_ICON_ARROW_RIGHT}}, {"30", {osi3::TrafficLight_Classification_Icon::TrafficLight_Classification_Icon_ICON_ARROW_STRAIGHT_AHEAD}}, @@ -458,7 +458,7 @@ namespace OpenDriveTypeMapper }, {"1.000.008", { - {"", {osi3::TrafficLight_Classification_Color::TrafficLight_Classification_Color_COLOR_YELLOW}}, + {"-1", {osi3::TrafficLight_Classification_Color::TrafficLight_Classification_Color_COLOR_YELLOW}}, {"10", {osi3::TrafficLight_Classification_Color::TrafficLight_Classification_Color_COLOR_YELLOW}}, {"20", {osi3::TrafficLight_Classification_Color::TrafficLight_Classification_Color_COLOR_YELLOW}}, {"30", {osi3::TrafficLight_Classification_Color::TrafficLight_Classification_Color_COLOR_YELLOW}}, @@ -470,7 +470,7 @@ namespace OpenDriveTypeMapper }, {"1.000.012", { - {"", {osi3::TrafficLight_Classification_Color::TrafficLight_Classification_Color_COLOR_GREEN}}, + {"-1", {osi3::TrafficLight_Classification_Color::TrafficLight_Classification_Color_COLOR_GREEN}}, {"10", {osi3::TrafficLight_Classification_Color::TrafficLight_Classification_Color_COLOR_GREEN}}, {"20", {osi3::TrafficLight_Classification_Color::TrafficLight_Classification_Color_COLOR_GREEN}}, {"30", {osi3::TrafficLight_Classification_Color::TrafficLight_Classification_Color_COLOR_GREEN}}, @@ -482,7 +482,7 @@ namespace OpenDriveTypeMapper }, {"1.000.020", { - {"", {osi3::TrafficLight_Classification_Color::TrafficLight_Classification_Color_COLOR_RED}}, + {"-1", {osi3::TrafficLight_Classification_Color::TrafficLight_Classification_Color_COLOR_RED}}, {"10", {osi3::TrafficLight_Classification_Color::TrafficLight_Classification_Color_COLOR_RED}}, {"20", {osi3::TrafficLight_Classification_Color::TrafficLight_Classification_Color_COLOR_RED}}, {"30", {osi3::TrafficLight_Classification_Color::TrafficLight_Classification_Color_COLOR_RED}}, diff --git a/sim/src/core/opSimulation/modules/World_OSI/OWL/TrafficLight.cpp b/sim/src/core/opSimulation/modules/World_OSI/OWL/TrafficLight.cpp index f4a65f163..92cc48dd2 100644 --- a/sim/src/core/opSimulation/modules/World_OSI/OWL/TrafficLight.cpp +++ b/sim/src/core/opSimulation/modules/World_OSI/OWL/TrafficLight.cpp @@ -86,15 +86,16 @@ TrafficLightBase::fetchColorsFromSignal(RoadSignalInterface *signal, const std:: auto colorTypeSet = helper::map::query(colorMap, signal->GetType()); if (!colorTypeSet.has_value()) { - LOGERROR("Could not get colorTypeSet for trafficlight signal \"" + signal->GetType()); + LOGERROR("Could not get colorTypeSet for trafficlight signal \"" + signal->GetType() + "\""); return {osi3::TrafficLight_Classification_Color_COLOR_UNKNOWN}; } auto colors = helper::map::query(colorTypeSet.value(), signal->GetSubType()); + if (!colors.has_value()) { - LOGERROR("Could not get color spec for trafficlight signal \"" + signal->GetType() + "and subtype " + signal->GetSubType()); + LOGERROR("Could not get color spec for trafficlight signal \"" + signal->GetType() + "\" and subtype \"" + signal->GetSubType() + "\""); return {osi3::TrafficLight_Classification_Color_COLOR_UNKNOWN}; } @@ -105,15 +106,15 @@ osi3::TrafficLight_Classification_Icon TrafficLightBase::fetchIconsFromSignal(Ro const std::map<std::string, std::map<std::string, osi3::TrafficLight_Classification_Icon>> &iconMap) { auto type = helper::map::query(iconMap, signal->GetType()); - if (!type.has_value()) { - LOGERROR("Could not get Icons for trafficlight signal \"" + signal->GetType()); + LOGERROR("Could not get Icons for trafficlight signal \"" + signal->GetType() + "\"") ; return osi3::TrafficLight_Classification_Icon_ICON_UNKNOWN; } - auto icons = helper::map::query(type.value(), signal->GetSubType()); + auto icons = helper::map::query(type.value(), signal->GetSubType()); + if (!icons.has_value()) { - LOGERROR("Could not get icon spec for trafficlight signal \"" + signal->GetType() + "and subtype " + signal->GetSubType()); + LOGERROR("Could not get icon spec for trafficlight signal \"" + signal->GetType() + "\" and subtype \"" + signal->GetSubType() + "\""); return osi3::TrafficLight_Classification_Icon_ICON_UNKNOWN; } @@ -529,7 +530,7 @@ bool OWL::Implementation::TwoSignalsTrafficLight::SetSpecificationOnOsiObject osiTrafficLightObject->mutable_classification()->set_color(colors[colorIndex]); return true; } else { - LOGERROR("Colors from the \"" + signal->GetType() + "and subtype " + signal->GetSubType()); + LOGERROR("Colors from the \"" + signal->GetType() + "\" and subtype \"" + signal->GetSubType() + "\""); return false; } } @@ -654,7 +655,7 @@ bool OWL::Implementation::OneSignalsTrafficLight::SetSpecificationOnOsiObject osiTrafficLightObject->mutable_classification()->set_color(colors[0]); return true; } else { - LOGERROR("Colors from the \"" + signal->GetType() + "and subtype " + signal->GetSubType()); + LOGERROR("Colors from the \"" + signal->GetType() + "\" and subtype \"" + signal->GetSubType() + "\""); return false; } } diff --git a/sim/tests/integrationTests/opSimulation_IntegrationTests/Resources/ImporterTest/IntegrationTestScenery.xodr b/sim/tests/integrationTests/opSimulation_IntegrationTests/Resources/ImporterTest/IntegrationTestScenery.xodr index bf49f4abd..808171023 100644 --- a/sim/tests/integrationTests/opSimulation_IntegrationTests/Resources/ImporterTest/IntegrationTestScenery.xodr +++ b/sim/tests/integrationTests/opSimulation_IntegrationTests/Resources/ImporterTest/IntegrationTestScenery.xodr @@ -205,10 +205,10 @@ This scenery consists of linear sections only. </signal> <signal id="4" type="531" subtype="21" s="36" t="-8" width="0.5" height="1.0" zOffset="1.5" hOffset="0" pitch="0" roll="0" dynamic="no" country="DE" name="" orientation="+"> </signal> - <signal id="5" type="206" subtype="" s="40" t="-8" width="0.4" height="0.4" zOffset="1.5" hOffset="0" pitch="0" roll="0" dynamic="no" country="DE" name="" orientation="+"> + <signal id="5" type="206" subtype="-1" s="40" t="-8" width="0.4" height="0.4" zOffset="1.5" hOffset="0" pitch="0" roll="0" dynamic="no" country="DE" name="" orientation="+"> <validity toLane="-2" fromLane="-2"/> </signal> - <signal id="6" type="294" subtype="" s="41" t="-7" width="4.0" hOffset="0" pitch="0" roll="0" dynamic="no" country="DE" name="" orientation="+" zOffset="0"> + <signal id="6" type="294" subtype="none" s="41" t="-7" width="4.0" hOffset="0" pitch="0" roll="0" dynamic="no" country="DE" name="" orientation="+" zOffset="0"> <validity toLane="-2" fromLane="-2"/> </signal> <signal id="7" type="1004" subtype="30" value="200" s="40" t="-8" width="0.4" height="0.2" hOffset="0" zOffset="1.2" pitch="0" roll="0" dynamic="no" country="DE" name="" orientation="+"> diff --git a/sim/tests/unitTests/core/opSimulation/modules/World_OSI/datatypes_Tests.cpp b/sim/tests/unitTests/core/opSimulation/modules/World_OSI/datatypes_Tests.cpp index 6e7c69f6d..f901c7618 100644 --- a/sim/tests/unitTests/core/opSimulation/modules/World_OSI/datatypes_Tests.cpp +++ b/sim/tests/unitTests/core/opSimulation/modules/World_OSI/datatypes_Tests.cpp @@ -425,7 +425,7 @@ TEST(TrafficLights, SetSpecification_TwoLights_13) { FakeRoadSignal roadSignal; ON_CALL(roadSignal, GetType()).WillByDefault(Return("1.000.013")); - ON_CALL(roadSignal, GetSubType()).WillByDefault(Return("")); + ON_CALL(roadSignal, GetSubType()).WillByDefault(Return("-1")); ON_CALL(roadSignal, GetWidth()).WillByDefault(Return(0.1)); ON_CALL(roadSignal, GetHeight()).WillByDefault(Return(0.2)); Position position{}; @@ -562,7 +562,7 @@ TEST(TrafficLights, SetSpecification_TwoLights_Pedestrian) { FakeRoadSignal roadSignal; ON_CALL(roadSignal, GetType()).WillByDefault(Return("1.000.002")); - ON_CALL(roadSignal, GetSubType()).WillByDefault(Return("")); + ON_CALL(roadSignal, GetSubType()).WillByDefault(Return("-1")); ON_CALL(roadSignal, GetWidth()).WillByDefault(Return(0.1)); ON_CALL(roadSignal, GetHeight()).WillByDefault(Return(0.2)); Position position{}; @@ -590,7 +590,7 @@ TEST(TrafficLights, SetSpecification_TwoLights_PedestrianAndBike) { FakeRoadSignal roadSignal; ON_CALL(roadSignal, GetType()).WillByDefault(Return("1.000.007")); - ON_CALL(roadSignal, GetSubType()).WillByDefault(Return("")); + ON_CALL(roadSignal, GetSubType()).WillByDefault(Return("-1")); ON_CALL(roadSignal, GetWidth()).WillByDefault(Return(0.1)); ON_CALL(roadSignal, GetHeight()).WillByDefault(Return(0.2)); Position position{}; @@ -657,7 +657,7 @@ TEST(TrafficLights, SetSpecification_OneLight_WithArrows_Red) { FakeRoadSignal roadSignal; ON_CALL(roadSignal, GetType()).WillByDefault(Return("1.000.020")); - ON_CALL(roadSignal, GetSubType()).WillByDefault(Return("")); + ON_CALL(roadSignal, GetSubType()).WillByDefault(Return("-1")); ON_CALL(roadSignal, GetWidth()).WillByDefault(Return(0.1)); ON_CALL(roadSignal, GetHeight()).WillByDefault(Return(0.2)); Position position{}; @@ -700,7 +700,7 @@ TEST(TrafficLights, SetSpecification_OneLight_WithArrows_Yellow) { FakeRoadSignal roadSignal; ON_CALL(roadSignal, GetType()).WillByDefault(Return("1.000.008")); - ON_CALL(roadSignal, GetSubType()).WillByDefault(Return("")); + ON_CALL(roadSignal, GetSubType()).WillByDefault(Return("-1")); ON_CALL(roadSignal, GetWidth()).WillByDefault(Return(0.1)); ON_CALL(roadSignal, GetHeight()).WillByDefault(Return(0.2)); Position position{}; @@ -743,7 +743,7 @@ TEST(TrafficLights, SetSpecification_OneLight_WithArrows_Green) { FakeRoadSignal roadSignal; ON_CALL(roadSignal, GetType()).WillByDefault(Return("1.000.012")); - ON_CALL(roadSignal, GetSubType()).WillByDefault(Return("")); + ON_CALL(roadSignal, GetSubType()).WillByDefault(Return("-1")); ON_CALL(roadSignal, GetWidth()).WillByDefault(Return(0.1)); ON_CALL(roadSignal, GetHeight()).WillByDefault(Return(0.2)); Position position{}; @@ -835,7 +835,7 @@ TEST(TrafficLights, SetSpecification_SetsCorrectBaseTwoSignalTrafficLight) ON_CALL(roadSignal, GetHOffset()).WillByDefault(Return(1.0)); ON_CALL(roadSignal, GetOrientation()).WillByDefault(Return(false)); ON_CALL(roadSignal, GetType()).WillByDefault(Return("1.000.002")); - ON_CALL(roadSignal, GetSubType()).WillByDefault(Return("")); + ON_CALL(roadSignal, GetSubType()).WillByDefault(Return("-1")); Position position{10, 11, 1.5, 0}; osi3::TrafficLight osiLightRed; diff --git a/sim/tests/unitTests/core/opSimulation/sceneryImporter_Tests.cpp b/sim/tests/unitTests/core/opSimulation/sceneryImporter_Tests.cpp index 5a188e24e..5df5f9000 100644 --- a/sim/tests/unitTests/core/opSimulation/sceneryImporter_Tests.cpp +++ b/sim/tests/unitTests/core/opSimulation/sceneryImporter_Tests.cpp @@ -123,7 +123,7 @@ TEST(SceneryImporter_UnitTests, ParseSignalsWithValidSignal_ReturnsCorrectValues EXPECT_DOUBLE_EQ(SignalInterceptor::signal.zOffset, 0.1); EXPECT_EQ(SignalInterceptor::signal.country, "c1"); EXPECT_EQ(SignalInterceptor::signal.type, "none"); - EXPECT_EQ(SignalInterceptor::signal.subtype, "none"); + EXPECT_EQ(SignalInterceptor::signal.subtype, "-1"); //accoount for openDrive standard 1.6, subtype of "none" and "" are parsed to "-1" EXPECT_DOUBLE_EQ(SignalInterceptor::signal.value, 0.123); EXPECT_EQ(SignalInterceptor::signal.unit, RoadSignalUnit::Undefined); EXPECT_DOUBLE_EQ(SignalInterceptor::signal.height, 1.01); -- GitLab