diff --git a/common/component_interface_specs/include/component_interface_specs/map.hpp b/common/component_interface_specs/include/component_interface_specs/map.hpp index f0cce7a7f97a2..dc162d4a7267a 100644 --- a/common/component_interface_specs/include/component_interface_specs/map.hpp +++ b/common/component_interface_specs/include/component_interface_specs/map.hpp @@ -25,7 +25,7 @@ namespace map_interface struct MapProjectorInfo { using Message = tier4_map_msgs::msg::MapProjectorInfo; - static constexpr char name[] = "/map/map_projector_type"; + static constexpr char name[] = "/map/map_projector_info"; static constexpr size_t depth = 1; static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE; static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL; diff --git a/launch/tier4_map_launch/launch/map.launch.py b/launch/tier4_map_launch/launch/map.launch.py index 169c53814df22..315ac2cf2eb90 100644 --- a/launch/tier4_map_launch/launch/map.launch.py +++ b/launch/tier4_map_launch/launch/map.launch.py @@ -64,7 +64,7 @@ def launch_setup(context, *args, **kwargs): name="lanelet2_map_loader", remappings=[ ("output/lanelet2_map", "vector_map"), - ("input/map_projector_info", "map_projector_type"), + ("input/map_projector_info", "map_projector_info"), ], parameters=[ { diff --git a/map/map_loader/README.md b/map/map_loader/README.md index 44f215b2d8c01..4c64eb1eaecae 100644 --- a/map/map_loader/README.md +++ b/map/map_loader/README.md @@ -140,7 +140,7 @@ Please see [the description of `GetSelectedPointCloudMap.srv`](https://github.co ### Feature lanelet2_map_loader loads Lanelet2 file and publishes the map data as autoware_auto_mapping_msgs/HADMapBin message. -The node projects lan/lon coordinates into arbitrary coordinates defined in `/map/map_projector_type` from `map_projection_loader`. +The node projects lan/lon coordinates into arbitrary coordinates defined in `/map/map_projector_info` from `map_projection_loader`. The node supports the following three types of coordinate systems: - MGRS diff --git a/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp b/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp index 2fb8b893d8fce..b4e903eaa7561 100644 --- a/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp +++ b/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp @@ -43,7 +43,7 @@ class Lanelet2MapLoaderNode : public rclcpp::Node private: void on_map_projector_info(const MapProjectorInfo::ConstSharedPtr msg); - rclcpp::Subscription::SharedPtr sub_map_projector_type_; + rclcpp::Subscription::SharedPtr sub_map_projector_info_; rclcpp::Publisher::SharedPtr pub_map_bin_; }; diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp index 42c46e2b5e96c..ac910b8f769df 100644 --- a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp +++ b/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp @@ -52,7 +52,7 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options : Node("lanelet2_map_loader", options) { // subscription - sub_map_projector_type_ = create_subscription( + sub_map_projector_info_ = create_subscription( "input/map_projector_info", rclcpp::QoS{1}.transient_local(), [this](const MapProjectorInfo::ConstSharedPtr msg) { on_map_projector_info(msg); }); } diff --git a/map/map_projection_loader/launch/map_projection_loader.launch.xml b/map/map_projection_loader/launch/map_projection_loader.launch.xml index 6448675c4a75f..6536dad6a4e21 100644 --- a/map/map_projection_loader/launch/map_projection_loader.launch.xml +++ b/map/map_projection_loader/launch/map_projection_loader.launch.xml @@ -3,7 +3,7 @@ - +