diff --git a/common/autoware_lanelet2_utils/include/autoware/lanelet2_utils/intersection.hpp b/common/autoware_lanelet2_utils/include/autoware/lanelet2_utils/intersection.hpp index 88206d5a05..f8d02a67ce 100644 --- a/common/autoware_lanelet2_utils/include/autoware/lanelet2_utils/intersection.hpp +++ b/common/autoware_lanelet2_utils/include/autoware/lanelet2_utils/intersection.hpp @@ -19,7 +19,7 @@ #include -namespace autoware::lanelet2_utils +namespace autoware::experimental::lanelet2_utils { static constexpr const char * k_turn_direction = "turn_direction"; @@ -68,5 +68,5 @@ bool is_right_direction(const lanelet::ConstLanelet & lanelet); */ std::optional get_turn_direction(const lanelet::ConstLanelet & lanelet); -} // namespace autoware::lanelet2_utils +} // namespace autoware::experimental::lanelet2_utils #endif // AUTOWARE__LANELET2_UTILS__INTERSECTION_HPP_ diff --git a/common/autoware_lanelet2_utils/include/autoware/lanelet2_utils/kind.hpp b/common/autoware_lanelet2_utils/include/autoware/lanelet2_utils/kind.hpp index 330e92d72d..79e9e046d4 100644 --- a/common/autoware_lanelet2_utils/include/autoware/lanelet2_utils/kind.hpp +++ b/common/autoware_lanelet2_utils/include/autoware/lanelet2_utils/kind.hpp @@ -17,7 +17,7 @@ #include -namespace autoware::lanelet2_utils +namespace autoware::experimental::lanelet2_utils { static constexpr const char * k_road_lane_type = "road"; static constexpr const char * k_shoulder_lane_type = "road_shoulder"; @@ -58,5 +58,5 @@ bool is_shoulder_lane(const lanelet::ConstLanelet & lanelet); * @return if the lanelet is bicycle_lane or not */ bool is_bicycle_lane(const lanelet::ConstLanelet & lanelet); -} // namespace autoware::lanelet2_utils +} // namespace autoware::experimental::lanelet2_utils #endif // AUTOWARE__LANELET2_UTILS__KIND_HPP_ diff --git a/common/autoware_lanelet2_utils/include/autoware/lanelet2_utils/topology.hpp b/common/autoware_lanelet2_utils/include/autoware/lanelet2_utils/topology.hpp index 5f9207b756..b3203c4b65 100644 --- a/common/autoware_lanelet2_utils/include/autoware/lanelet2_utils/topology.hpp +++ b/common/autoware_lanelet2_utils/include/autoware/lanelet2_utils/topology.hpp @@ -22,7 +22,7 @@ #include #include -namespace autoware::lanelet2_utils +namespace autoware::experimental::lanelet2_utils { /** * @brief instantiate RoutingGraph from given LaneletMap only from "road" lanes @@ -181,6 +181,6 @@ lanelet::ConstLanelets sibling_lanelets( */ lanelet::ConstLanelets from_ids( const lanelet::LaneletMapConstPtr lanelet_map, const std::vector & ids); -} // namespace autoware::lanelet2_utils +} // namespace autoware::experimental::lanelet2_utils #endif // AUTOWARE__LANELET2_UTILS__TOPOLOGY_HPP_ diff --git a/common/autoware_lanelet2_utils/src/intersection.cpp b/common/autoware_lanelet2_utils/src/intersection.cpp index 710dd5e3ed..6dea4e1a3f 100644 --- a/common/autoware_lanelet2_utils/src/intersection.cpp +++ b/common/autoware_lanelet2_utils/src/intersection.cpp @@ -17,7 +17,7 @@ #include #include -namespace autoware::lanelet2_utils +namespace autoware::experimental::lanelet2_utils { bool is_intersection_lanelet(const lanelet::ConstLanelet & lanelet) @@ -54,4 +54,4 @@ std::optional get_turn_direction(const lanelet::ConstLanelet & la return std::nullopt; } -} // namespace autoware::lanelet2_utils +} // namespace autoware::experimental::lanelet2_utils diff --git a/common/autoware_lanelet2_utils/src/kind.cpp b/common/autoware_lanelet2_utils/src/kind.cpp index 824f09f146..9b4cb0d253 100644 --- a/common/autoware_lanelet2_utils/src/kind.cpp +++ b/common/autoware_lanelet2_utils/src/kind.cpp @@ -17,7 +17,7 @@ #include #include -namespace autoware::lanelet2_utils +namespace autoware::experimental::lanelet2_utils { bool is_road_lane(const lanelet::ConstLanelet & lanelet) { @@ -36,4 +36,4 @@ bool is_bicycle_lane(const lanelet::ConstLanelet & lanelet) return std::strcmp( lanelet.attributeOr(lanelet::AttributeName::Subtype, "none"), k_bicycle_lane_type) == 0; } -} // namespace autoware::lanelet2_utils +} // namespace autoware::experimental::lanelet2_utils diff --git a/common/autoware_lanelet2_utils/src/topology.cpp b/common/autoware_lanelet2_utils/src/topology.cpp index d3f64f995e..9b8a669de5 100644 --- a/common/autoware_lanelet2_utils/src/topology.cpp +++ b/common/autoware_lanelet2_utils/src/topology.cpp @@ -21,7 +21,7 @@ #include -namespace autoware::lanelet2_utils +namespace autoware::experimental::lanelet2_utils { static constexpr size_t k_normal_bundle_max_size = 10; @@ -262,4 +262,4 @@ lanelet::ConstLanelets from_ids( }) | ranges::to(); } -} // namespace autoware::lanelet2_utils +} // namespace autoware::experimental::lanelet2_utils diff --git a/common/autoware_lanelet2_utils/test/intersection.cpp b/common/autoware_lanelet2_utils/test/intersection.cpp index 47e2030d46..4ccc9860e1 100644 --- a/common/autoware_lanelet2_utils/test/intersection.cpp +++ b/common/autoware_lanelet2_utils/test/intersection.cpp @@ -24,7 +24,7 @@ namespace fs = std::filesystem; -namespace autoware +namespace autoware::experimental { class TestWithIntersectionCrossingMap : public ::testing::Test { @@ -110,7 +110,7 @@ TEST_F(TestWithIntersectionCrossingMap, get_turn_direction) } } -} // namespace autoware +} // namespace autoware::experimental int main(int argc, char ** argv) { diff --git a/common/autoware_lanelet2_utils/test/kind.cpp b/common/autoware_lanelet2_utils/test/kind.cpp index 8cdc6dca14..996f958c60 100644 --- a/common/autoware_lanelet2_utils/test/kind.cpp +++ b/common/autoware_lanelet2_utils/test/kind.cpp @@ -24,7 +24,7 @@ namespace fs = std::filesystem; -namespace autoware +namespace autoware::experimental { class TestWithRoadShoulderHighwayMap : public ::testing::Test { @@ -88,7 +88,7 @@ TEST_F(TestWithIntersectionCrossingMap, is_shoulder_lane) EXPECT_EQ(lanelet2_utils::is_shoulder_lane(ll), false); EXPECT_EQ(lanelet2_utils::is_bicycle_lane(ll), true); } -} // namespace autoware +} // namespace autoware::experimental int main(int argc, char ** argv) { diff --git a/common/autoware_lanelet2_utils/test/topology.cpp b/common/autoware_lanelet2_utils/test/topology.cpp index 915bf0cd43..e21b3c4fe0 100644 --- a/common/autoware_lanelet2_utils/test/topology.cpp +++ b/common/autoware_lanelet2_utils/test/topology.cpp @@ -28,7 +28,7 @@ namespace fs = std::filesystem; -namespace autoware +namespace autoware::experimental { class TestWithIntersectionCrossingMap : public ::testing::Test @@ -289,7 +289,7 @@ TEST_F(TestWithIntersectionCrossingInverseMap, left_lanelets_with_opposite_witho EXPECT_EQ(lefts[0].id(), 2252); } -} // namespace autoware +} // namespace autoware::experimental int main(int argc, char ** argv) {