diff --git a/autoware_lanelet2_extension/README.md b/autoware_lanelet2_extension/README.md index 2c7badc..b7dadd7 100644 --- a/autoware_lanelet2_extension/README.md +++ b/autoware_lanelet2_extension/README.md @@ -54,7 +54,7 @@ Autoware intersection module requires the information on which lanes can be igno This contains functions to convert lanelet map objects into ROS messages. Currently it contains following conversions: -- lanelet::LaneletMapPtr to/from autoware_auto_mapping_msgs::msg::HADMapBin +- lanelet::LaneletMapPtr to/from autoware_map_msgs::msg::LaneletMapBin - lanelet::Point3d to geometry_msgs::Point - lanelet::Point2d to geometry_msgs::Point - lanelet::BasicPoint3d to geometry_msgs::Point diff --git a/autoware_lanelet2_extension/include/autoware_lanelet2_extension/localization/landmark.hpp b/autoware_lanelet2_extension/include/autoware_lanelet2_extension/localization/landmark.hpp index 7c96cef..950fb8c 100644 --- a/autoware_lanelet2_extension/include/autoware_lanelet2_extension/localization/landmark.hpp +++ b/autoware_lanelet2_extension/include/autoware_lanelet2_extension/localization/landmark.hpp @@ -15,7 +15,7 @@ #ifndef LANELET2_EXTENSION__LOCALIZATION__LANDMARK_HPP_ #define LANELET2_EXTENSION__LOCALIZATION__LANDMARK_HPP_ -#include "autoware_auto_mapping_msgs/msg/had_map_bin.hpp" +#include #include @@ -28,7 +28,7 @@ namespace lanelet::localization { std::vector parseLandmarkPolygons( - const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg, + const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr & msg, const std::string & target_subtype); } // namespace lanelet::localization diff --git a/autoware_lanelet2_extension/include/autoware_lanelet2_extension/utility/message_conversion.hpp b/autoware_lanelet2_extension/include/autoware_lanelet2_extension/utility/message_conversion.hpp index f88e5ce..f9bd561 100644 --- a/autoware_lanelet2_extension/include/autoware_lanelet2_extension/utility/message_conversion.hpp +++ b/autoware_lanelet2_extension/include/autoware_lanelet2_extension/utility/message_conversion.hpp @@ -19,7 +19,7 @@ // NOLINTBEGIN(readability-identifier-naming) -#include +#include #include #include #include @@ -36,7 +36,7 @@ namespace lanelet::utils::conversion * @param map [lanelet map data] * @param msg [converted ROS message. Only "data" field is filled] */ -void toBinMsg(const lanelet::LaneletMapPtr & map, autoware_auto_mapping_msgs::msg::HADMapBin * msg); +void toBinMsg(const lanelet::LaneletMapPtr & map, autoware_map_msgs::msg::LaneletMapBin * msg); /** * [fromBinMsg converts ROS message into lanelet2 data. Similar implementation @@ -44,9 +44,9 @@ void toBinMsg(const lanelet::LaneletMapPtr & map, autoware_auto_mapping_msgs::ms * @param msg [ROS message for lanelet map] * @param map [Converted lanelet2 data] */ -void fromBinMsg(const autoware_auto_mapping_msgs::msg::HADMapBin & msg, lanelet::LaneletMapPtr map); +void fromBinMsg(const autoware_map_msgs::msg::LaneletMapBin & msg, lanelet::LaneletMapPtr map); void fromBinMsg( - const autoware_auto_mapping_msgs::msg::HADMapBin & msg, lanelet::LaneletMapPtr map, + const autoware_map_msgs::msg::LaneletMapBin & msg, lanelet::LaneletMapPtr map, lanelet::traffic_rules::TrafficRulesPtr * traffic_rules, lanelet::routing::RoutingGraphPtr * routing_graph); diff --git a/autoware_lanelet2_extension/lib/landmark.cpp b/autoware_lanelet2_extension/lib/landmark.cpp index 9c349aa..8a8ec11 100644 --- a/autoware_lanelet2_extension/lib/landmark.cpp +++ b/autoware_lanelet2_extension/lib/landmark.cpp @@ -24,7 +24,7 @@ namespace lanelet::localization { std::vector parseLandmarkPolygons( - const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg, + const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr & msg, const std::string & target_subtype) { lanelet::LaneletMapPtr lanelet_map_ptr{std::make_shared()}; diff --git a/autoware_lanelet2_extension/lib/message_conversion.cpp b/autoware_lanelet2_extension/lib/message_conversion.cpp index 4d823f0..350e8f6 100644 --- a/autoware_lanelet2_extension/lib/message_conversion.cpp +++ b/autoware_lanelet2_extension/lib/message_conversion.cpp @@ -39,7 +39,7 @@ namespace lanelet::utils::conversion { -void toBinMsg(const lanelet::LaneletMapPtr & map, autoware_auto_mapping_msgs::msg::HADMapBin * msg) +void toBinMsg(const lanelet::LaneletMapPtr & map, autoware_map_msgs::msg::LaneletMapBin * msg) { if (msg == nullptr) { std::cerr << __FUNCTION__ << "msg is null pointer!"; @@ -58,7 +58,7 @@ void toBinMsg(const lanelet::LaneletMapPtr & map, autoware_auto_mapping_msgs::ms msg->data.assign(data_str.begin(), data_str.end()); } -void fromBinMsg(const autoware_auto_mapping_msgs::msg::HADMapBin & msg, lanelet::LaneletMapPtr map) +void fromBinMsg(const autoware_map_msgs::msg::LaneletMapBin & msg, lanelet::LaneletMapPtr map) { if (!map) { std::cerr << __FUNCTION__ << ": map is null pointer!"; @@ -79,7 +79,7 @@ void fromBinMsg(const autoware_auto_mapping_msgs::msg::HADMapBin & msg, lanelet: } void fromBinMsg( - const autoware_auto_mapping_msgs::msg::HADMapBin & msg, lanelet::LaneletMapPtr map, + const autoware_map_msgs::msg::LaneletMapBin & msg, lanelet::LaneletMapPtr map, lanelet::traffic_rules::TrafficRulesPtr * traffic_rules, lanelet::routing::RoutingGraphPtr * routing_graph) { diff --git a/autoware_lanelet2_extension/package.xml b/autoware_lanelet2_extension/package.xml index e5b0f41..2e7291d 100644 --- a/autoware_lanelet2_extension/package.xml +++ b/autoware_lanelet2_extension/package.xml @@ -15,8 +15,7 @@ ament_cmake_auto autoware_cmake - autoware_auto_mapping_msgs - autoware_auto_planning_msgs + autoware_map_msgs autoware_planning_msgs autoware_utils geographiclib diff --git a/autoware_lanelet2_extension/test/src/test_message_conversion.cpp b/autoware_lanelet2_extension/test/src/test_message_conversion.cpp index 7643262..ad1c7a9 100644 --- a/autoware_lanelet2_extension/test/src/test_message_conversion.cpp +++ b/autoware_lanelet2_extension/test/src/test_message_conversion.cpp @@ -67,7 +67,7 @@ class TestSuite : public ::testing::Test // NOLINT for gtest TEST_F(TestSuite, BinMsgConversion) // NOLINT for gtest { - autoware_auto_mapping_msgs::msg::HADMapBin bin_msg; + autoware_map_msgs::msg::LaneletMapBin bin_msg; lanelet::LaneletMapPtr regenerated_map(new lanelet::LaneletMap); lanelet::utils::conversion::toBinMsg(single_lanelet_map_ptr, &bin_msg); diff --git a/autoware_lanelet2_extension/test/src/test_route_checker.cpp b/autoware_lanelet2_extension/test/src/test_route_checker.cpp index 12525fa..11ab65e 100644 --- a/autoware_lanelet2_extension/test/src/test_route_checker.cpp +++ b/autoware_lanelet2_extension/test/src/test_route_checker.cpp @@ -17,7 +17,7 @@ #include "autoware_lanelet2_extension/utility/message_conversion.hpp" #include "autoware_lanelet2_extension/utility/route_checker.hpp" -#include +#include #include #include @@ -74,7 +74,7 @@ class TestSuite : public ::testing::Test // NOLINT for gtest TEST_F(TestSuite, isRouteValid) // NOLINT for gtest { - autoware_auto_mapping_msgs::msg::HADMapBin bin_msg; + autoware_map_msgs::msg::LaneletMapBin bin_msg; const auto route_ptr1 = std::make_shared(sample_route1); diff --git a/build_depends.repos b/build_depends.repos index 89e4b62..7008065 100644 --- a/build_depends.repos +++ b/build_depends.repos @@ -1,8 +1,4 @@ repositories: - autoware_auto_msgs: - type: git - url: https://github.com/tier4/autoware_auto_msgs.git - version: tier4/main autoware_cmake: type: git url: https://github.com/autowarefoundation/autoware_cmake.git