diff --git a/autoware_lanelet2_extension/include/autoware_lanelet2_extension/regulatory_elements/bus_stop_area.hpp b/autoware_lanelet2_extension/include/autoware_lanelet2_extension/regulatory_elements/bus_stop_area.hpp index 72b2986..f2f2be2 100644 --- a/autoware_lanelet2_extension/include/autoware_lanelet2_extension/regulatory_elements/bus_stop_area.hpp +++ b/autoware_lanelet2_extension/include/autoware_lanelet2_extension/regulatory_elements/bus_stop_area.hpp @@ -44,8 +44,8 @@ class BusStopArea : public lanelet::RegulatoryElement * @brief get the relevant bus stop area * @return bus stop area */ - [[nodiscard]] ConstPolygons3d BusStopAreas() const; - [[nodiscard]] Polygons3d BusStopAreas(); + [[nodiscard]] ConstPolygons3d busStopAreas() const; + [[nodiscard]] Polygons3d busStopAreas(); /** * @brief add a new bus stop are diff --git a/autoware_lanelet2_extension/lib/bus_stop_area.cpp b/autoware_lanelet2_extension/lib/bus_stop_area.cpp index 059ab4e..b2f5a5a 100644 --- a/autoware_lanelet2_extension/lib/bus_stop_area.cpp +++ b/autoware_lanelet2_extension/lib/bus_stop_area.cpp @@ -83,9 +83,9 @@ ConstPolygons3d getConstPoly(const RuleParameterMap & params, RoleName role) } RegulatoryElementDataPtr constructBusStopAreaData( - Id id, const AttributeMap & attributes, const Polygons3d & BusStopAreas) + Id id, const AttributeMap & attributes, const Polygons3d & bus_stop_areas) { - RuleParameterMap rpm = {{RoleNameString::Refers, toRuleParameters(BusStopAreas)}}; + RuleParameterMap rpm = {{RoleNameString::Refers, toRuleParameters(bus_stop_areas)}}; auto data = std::make_shared(id, std::move(rpm), attributes); data->attributes[AttributeName::Type] = AttributeValueString::RegulatoryElement; @@ -100,7 +100,7 @@ namespace format_v2 BusStopArea::BusStopArea(const RegulatoryElementDataPtr & data) : RegulatoryElement(data) { if (getConstPoly(data->parameters, RoleName::Refers).empty()) { - throw InvalidInputError("no parking area defined!"); + throw InvalidInputError("no bus stop area defined!"); } } @@ -109,11 +109,11 @@ BusStopArea::BusStopArea(Id id, const AttributeMap & attributes, const Polygons3 { } -ConstPolygons3d BusStopArea::BusStopAreas() const +ConstPolygons3d BusStopArea::busStopAreas() const { return getConstPoly(parameters(), RoleName::Refers); } -Polygons3d BusStopArea::BusStopAreas() +Polygons3d BusStopArea::busStopAreas() { return getPoly(parameters(), RoleName::Refers); } diff --git a/autoware_lanelet2_extension/test/src/test_regulatory_elements.cpp b/autoware_lanelet2_extension/test/src/test_regulatory_elements.cpp index a7d9ff8..61efe62 100644 --- a/autoware_lanelet2_extension/test/src/test_regulatory_elements.cpp +++ b/autoware_lanelet2_extension/test/src/test_regulatory_elements.cpp @@ -15,6 +15,7 @@ // NOLINTBEGIN(readability-identifier-naming) #include "autoware_lanelet2_extension/regulatory_elements/autoware_traffic_light.hpp" +#include "autoware_lanelet2_extension/regulatory_elements/bus_stop_area.hpp" #include @@ -29,6 +30,7 @@ using lanelet::LineString3d; using lanelet::LineStringOrPolygon3d; using lanelet::Point3d; using lanelet::Points3d; +using lanelet::Polygon3d; using lanelet::utils::getId; namespace @@ -138,6 +140,27 @@ TEST(TestSuite, TrafficLightWorksAsExpected) // NOLINT for gtest EXPECT_EQ(1ul, tl->lightBulbs().size()); } +TEST(TestSuite, BusStopAreInstantiation) // NOLINT for gtest +{ + /* + p4 <---- p3 + | ^ + | | + V | + p1 ----> p2 + */ + const Point3d p1{getId(), 0, 0, 0}; + const Point3d p2{getId(), 3, 0, 0}; + const Point3d p3{getId(), 3, 3, 0}; + const Point3d p4{getId(), 0, 3, 0}; + const Polygon3d polygon{LineString3d{getId(), Points3d{p1, p2, p3, p4}}}; + auto bus_stop_area_reg_elem = lanelet::autoware::format_v2::BusStopArea::make( + getId(), lanelet::AttributeMap(), convertToVector(polygon)); + EXPECT_EQ(bus_stop_area_reg_elem->busStopAreas().size(), 1); + EXPECT_NO_THROW(bus_stop_area_reg_elem->busStopAreas().at(0)); + const auto bus_stop_area = bus_stop_area_reg_elem->busStopAreas().at(0); +} + int main(int argc, char ** argv) { testing::InitGoogleTest(&argc, argv);