diff --git a/.github/CODEOWNERS b/.github/CODEOWNERS
index 61af2edc5b516..0097a386e47a7 100644
--- a/.github/CODEOWNERS
+++ b/.github/CODEOWNERS
@@ -97,6 +97,7 @@ localization/yabloc/yabloc_image_processing/** anh.nguyen.2@tier4.jp kento.yabuu
localization/yabloc/yabloc_monitor/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/yabloc/yabloc_particle_filter/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/yabloc/yabloc_pose_initializer/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
+map/autoware_lanelet2_map_visualizer/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
map/autoware_map_height_fitter/** anh.nguyen.2@tier4.jp isamu.takagi@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
map/autoware_map_projection_loader/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
map/autoware_map_tf_generator/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
diff --git a/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.cpp b/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.cpp
index 2165587493a7a..c4104584f3f3b 100644
--- a/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.cpp
+++ b/common/tier4_traffic_light_rviz_plugin/src/traffic_light_publish_panel.cpp
@@ -364,7 +364,7 @@ void TrafficLightPublishPanel::onTimer()
void TrafficLightPublishPanel::onVectorMap(const LaneletMapBin::ConstSharedPtr msg)
{
if (received_vector_map_) return;
- // NOTE: examples from map_loader/lanelet2_map_visualization_node.cpp
+ // NOTE: examples from autoware_lanelet2_map_visualizer/lanelet2_map_visualization_node.cpp
lanelet::LaneletMapPtr lanelet_map(new lanelet::LaneletMap);
lanelet::utils::conversion::fromBinMsg(*msg, lanelet_map);
lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map);
diff --git a/launch/tier4_map_launch/launch/map.launch.xml b/launch/tier4_map_launch/launch/map.launch.xml
index 3b30a891ae555..2fbdbc694cacc 100644
--- a/launch/tier4_map_launch/launch/map.launch.xml
+++ b/launch/tier4_map_launch/launch/map.launch.xml
@@ -20,7 +20,7 @@
-
+
@@ -31,13 +31,13 @@
-
+
-
+
@@ -47,7 +47,7 @@
-
+
diff --git a/launch/tier4_map_launch/package.xml b/launch/tier4_map_launch/package.xml
index ca2d46db38a52..a5120987605f5 100644
--- a/launch/tier4_map_launch/package.xml
+++ b/launch/tier4_map_launch/package.xml
@@ -18,9 +18,9 @@
ament_cmake_auto
autoware_cmake
+ autoware_map_loader
autoware_map_projection_loader
autoware_map_tf_generator
- map_loader
ament_lint_auto
autoware_lint_common
diff --git a/map/autoware_lanelet2_map_visualizer/CMakeLists.txt b/map/autoware_lanelet2_map_visualizer/CMakeLists.txt
new file mode 100644
index 0000000000000..5f2cb4a1f67a1
--- /dev/null
+++ b/map/autoware_lanelet2_map_visualizer/CMakeLists.txt
@@ -0,0 +1,18 @@
+cmake_minimum_required(VERSION 3.14)
+project(autoware_lanelet2_map_visualizer)
+
+find_package(autoware_cmake REQUIRED)
+autoware_package()
+
+ament_auto_add_library(lanelet2_map_visualization_node SHARED
+ src/lanelet2_map_visualization_node.cpp
+)
+
+rclcpp_components_register_node(lanelet2_map_visualization_node
+ PLUGIN "autoware::lanelet2_map_visualizer::Lanelet2MapVisualizationNode"
+ EXECUTABLE lanelet2_map_visualization
+)
+
+ament_auto_package(INSTALL_TO_SHARE
+ launch
+)
diff --git a/map/autoware_lanelet2_map_visualizer/README.md b/map/autoware_lanelet2_map_visualizer/README.md
new file mode 100644
index 0000000000000..b7e86b4a0d62b
--- /dev/null
+++ b/map/autoware_lanelet2_map_visualizer/README.md
@@ -0,0 +1,21 @@
+# autoware_lanelet2_map_visualizer package
+
+This package provides the features of visualizing the lanelet2 maps.
+
+## lanelet2_map_visualization
+
+### Feature
+
+lanelet2_map_visualization visualizes autoware_map_msgs/LaneletMapBin messages into visualization_msgs/MarkerArray.
+
+### How to Run
+
+`ros2 run autoware_lanelet2_map_visualizer lanelet2_map_visualization`
+
+### Subscribed Topics
+
+- ~input/lanelet2_map (autoware_map_msgs/LaneletMapBin) : binary data of Lanelet2 Map
+
+### Published Topics
+
+- ~output/lanelet2_map_marker (visualization_msgs/MarkerArray) : visualization messages for RViz
diff --git a/map/autoware_lanelet2_map_visualizer/launch/lanelet2_map_visualizer.launch.xml b/map/autoware_lanelet2_map_visualizer/launch/lanelet2_map_visualizer.launch.xml
new file mode 100644
index 0000000000000..6c6702c6e7904
--- /dev/null
+++ b/map/autoware_lanelet2_map_visualizer/launch/lanelet2_map_visualizer.launch.xml
@@ -0,0 +1,9 @@
+
+
+
+
+
+
+
+
+
diff --git a/map/autoware_lanelet2_map_visualizer/package.xml b/map/autoware_lanelet2_map_visualizer/package.xml
new file mode 100644
index 0000000000000..0244a5f010aa4
--- /dev/null
+++ b/map/autoware_lanelet2_map_visualizer/package.xml
@@ -0,0 +1,36 @@
+
+
+
+ autoware_lanelet2_map_visualizer
+ 0.1.0
+ The autoware_lanelet2_map_visualizer package
+ Yamato Ando
+ Ryu Yamamoto
+ Masahiro Sakamoto
+ Kento Yabuuchi
+ NGUYEN Viet Anh
+ Taiki Yamada
+ Shintaro Sakoda
+ Mamoru Sobue
+
+ Apache License 2.0
+ Ryohsuke Mitsudome
+ Koji Minoda
+
+ ament_cmake_auto
+ autoware_cmake
+
+ autoware_lanelet2_extension
+ autoware_map_msgs
+ rclcpp
+ rclcpp_components
+ tier4_map_msgs
+ visualization_msgs
+
+ ament_lint_auto
+ autoware_lint_common
+
+
+ ament_cmake
+
+
diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp b/map/autoware_lanelet2_map_visualizer/src/lanelet2_map_visualization_node.cpp
similarity index 98%
rename from map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp
rename to map/autoware_lanelet2_map_visualizer/src/lanelet2_map_visualization_node.cpp
index 4a9aae78e8eb3..ae9e7114cb385 100644
--- a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp
+++ b/map/autoware_lanelet2_map_visualizer/src/lanelet2_map_visualization_node.cpp
@@ -31,7 +31,7 @@
*
*/
-#include "map_loader/lanelet2_map_visualization_node.hpp"
+#include "lanelet2_map_visualization_node.hpp"
#include
#include
@@ -49,7 +49,7 @@
#include
#include
-namespace
+namespace autoware::lanelet2_map_visualizer
{
void insert_marker_array(
visualization_msgs::msg::MarkerArray * a1, const visualization_msgs::msg::MarkerArray & a2)
@@ -64,7 +64,6 @@ void set_color(std_msgs::msg::ColorRGBA * cl, double r, double g, double b, doub
cl->b = static_cast(b);
cl->a = static_cast(a);
}
-} // namespace
Lanelet2MapVisualizationNode::Lanelet2MapVisualizationNode(const rclcpp::NodeOptions & options)
: Node("lanelet2_map_visualization", options)
@@ -314,6 +313,7 @@ void Lanelet2MapVisualizationNode::on_map_bin(
pub_marker_->publish(map_marker_array);
}
+} // namespace autoware::lanelet2_map_visualizer
#include
-RCLCPP_COMPONENTS_REGISTER_NODE(Lanelet2MapVisualizationNode)
+RCLCPP_COMPONENTS_REGISTER_NODE(autoware::lanelet2_map_visualizer::Lanelet2MapVisualizationNode)
diff --git a/map/map_loader/include/map_loader/lanelet2_map_visualization_node.hpp b/map/autoware_lanelet2_map_visualizer/src/lanelet2_map_visualization_node.hpp
similarity index 83%
rename from map/map_loader/include/map_loader/lanelet2_map_visualization_node.hpp
rename to map/autoware_lanelet2_map_visualizer/src/lanelet2_map_visualization_node.hpp
index 049d714ec452a..7694c191f12a2 100644
--- a/map/map_loader/include/map_loader/lanelet2_map_visualization_node.hpp
+++ b/map/autoware_lanelet2_map_visualizer/src/lanelet2_map_visualization_node.hpp
@@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#ifndef MAP_LOADER__LANELET2_MAP_VISUALIZATION_NODE_HPP_
-#define MAP_LOADER__LANELET2_MAP_VISUALIZATION_NODE_HPP_
+#ifndef LANELET2_MAP_VISUALIZATION_NODE_HPP_
+#define LANELET2_MAP_VISUALIZATION_NODE_HPP_
#include
@@ -23,6 +23,8 @@
#include
#include
+namespace autoware::lanelet2_map_visualizer
+{
class Lanelet2MapVisualizationNode : public rclcpp::Node
{
public:
@@ -36,5 +38,6 @@ class Lanelet2MapVisualizationNode : public rclcpp::Node
void on_map_bin(const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr msg);
};
+} // namespace autoware::lanelet2_map_visualizer
-#endif // MAP_LOADER__LANELET2_MAP_VISUALIZATION_NODE_HPP_
+#endif // LANELET2_MAP_VISUALIZATION_NODE_HPP_
diff --git a/map/map_loader/CHANGELOG.rst b/map/autoware_map_loader/CHANGELOG.rst
similarity index 100%
rename from map/map_loader/CHANGELOG.rst
rename to map/autoware_map_loader/CHANGELOG.rst
diff --git a/map/map_loader/CMakeLists.txt b/map/autoware_map_loader/CMakeLists.txt
similarity index 84%
rename from map/map_loader/CMakeLists.txt
rename to map/autoware_map_loader/CMakeLists.txt
index 115f7e5b17464..9f8f8681488aa 100644
--- a/map/map_loader/CMakeLists.txt
+++ b/map/autoware_map_loader/CMakeLists.txt
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.14)
-project(map_loader)
+project(autoware_map_loader)
find_package(autoware_cmake REQUIRED)
autoware_package()
@@ -23,8 +23,8 @@ target_include_directories(pointcloud_map_loader_node
)
rclcpp_components_register_node(pointcloud_map_loader_node
- PLUGIN "PointCloudMapLoaderNode"
- EXECUTABLE pointcloud_map_loader
+ PLUGIN "autoware::map_loader::PointCloudMapLoaderNode"
+ EXECUTABLE autoware_pointcloud_map_loader
)
ament_auto_add_library(lanelet2_map_loader_node SHARED
@@ -32,17 +32,8 @@ ament_auto_add_library(lanelet2_map_loader_node SHARED
)
rclcpp_components_register_node(lanelet2_map_loader_node
- PLUGIN "Lanelet2MapLoaderNode"
- EXECUTABLE lanelet2_map_loader
-)
-
-ament_auto_add_library(lanelet2_map_visualization_node SHARED
- src/lanelet2_map_loader/lanelet2_map_visualization_node.cpp
-)
-
-rclcpp_components_register_node(lanelet2_map_visualization_node
- PLUGIN "Lanelet2MapVisualizationNode"
- EXECUTABLE lanelet2_map_visualization
+ PLUGIN "autoware::map_loader::Lanelet2MapLoaderNode"
+ EXECUTABLE autoware_lanelet2_map_loader
)
if(BUILD_TESTING)
diff --git a/map/map_loader/README.md b/map/autoware_map_loader/README.md
similarity index 91%
rename from map/map_loader/README.md
rename to map/autoware_map_loader/README.md
index bc3eb80d80339..046c9062081ca 100644
--- a/map/map_loader/README.md
+++ b/map/autoware_map_loader/README.md
@@ -1,4 +1,4 @@
-# map_loader package
+# autoware_map_loader package
This package provides the features of loading various maps.
@@ -111,7 +111,7 @@ Please see [the description of `GetSelectedPointCloudMap.srv`](https://github.co
### Parameters
-{{ json_to_markdown("map/map_loader/schema/pointcloud_map_loader.schema.json") }}
+{{ json_to_markdown("map/autoware_map_loader/schema/pointcloud_map_loader.schema.json") }}
### Interfaces
@@ -136,7 +136,7 @@ Please see [tier4_autoware_msgs/msg/MapProjectorInfo.msg](https://github.com/tie
### How to run
-`ros2 run map_loader lanelet2_map_loader --ros-args -p lanelet2_map_path:=path/to/map.osm`
+`ros2 run autoware_map_loader lanelet2_map_loader --ros-args -p lanelet2_map_path:=path/to/map.osm`
### Subscribed Topics
@@ -148,27 +148,7 @@ Please see [tier4_autoware_msgs/msg/MapProjectorInfo.msg](https://github.com/tie
### Parameters
-{{ json_to_markdown("map/map_loader/schema/lanelet2_map_loader.schema.json") }}
+{{ json_to_markdown("map/autoware_map_loader/schema/lanelet2_map_loader.schema.json") }}
`use_waypoints` decides how to handle a centerline.
This flag enables to use the `overwriteLaneletsCenterlineWithWaypoints` function instead of `overwriteLaneletsCenterline`. Please see [the document of the autoware_lanelet2_extension package](https://github.com/autowarefoundation/autoware_lanelet2_extension/blob/main/autoware_lanelet2_extension/docs/lanelet2_format_extension.md#centerline) in detail.
-
----
-
-## lanelet2_map_visualization
-
-### Feature
-
-lanelet2_map_visualization visualizes autoware_map_msgs/LaneletMapBin messages into visualization_msgs/MarkerArray.
-
-### How to Run
-
-`ros2 run map_loader lanelet2_map_visualization`
-
-### Subscribed Topics
-
-- ~input/lanelet2_map (autoware_map_msgs/LaneletMapBin) : binary data of Lanelet2 Map
-
-### Published Topics
-
-- ~output/lanelet2_map_marker (visualization_msgs/MarkerArray) : visualization messages for RViz
diff --git a/map/map_loader/config/lanelet2_map_loader.param.yaml b/map/autoware_map_loader/config/lanelet2_map_loader.param.yaml
similarity index 100%
rename from map/map_loader/config/lanelet2_map_loader.param.yaml
rename to map/autoware_map_loader/config/lanelet2_map_loader.param.yaml
diff --git a/map/map_loader/config/pointcloud_map_loader.param.yaml b/map/autoware_map_loader/config/pointcloud_map_loader.param.yaml
similarity index 100%
rename from map/map_loader/config/pointcloud_map_loader.param.yaml
rename to map/autoware_map_loader/config/pointcloud_map_loader.param.yaml
diff --git a/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp b/map/autoware_map_loader/include/autoware/map_loader/lanelet2_map_loader_node.hpp
similarity index 88%
rename from map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp
rename to map/autoware_map_loader/include/autoware/map_loader/lanelet2_map_loader_node.hpp
index 2d3fbfb2a140f..54d8244ff76e0 100644
--- a/map/map_loader/include/map_loader/lanelet2_map_loader_node.hpp
+++ b/map/autoware_map_loader/include/autoware/map_loader/lanelet2_map_loader_node.hpp
@@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-#ifndef MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_
-#define MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_
+#ifndef AUTOWARE__MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_
+#define AUTOWARE__MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_
#include
#include
@@ -28,6 +28,8 @@
#include
#include
+namespace autoware::map_loader
+{
class Lanelet2MapLoaderNode : public rclcpp::Node
{
public:
@@ -52,5 +54,6 @@ class Lanelet2MapLoaderNode : public rclcpp::Node
sub_map_projector_info_;
rclcpp::Publisher::SharedPtr pub_map_bin_;
};
+} // namespace autoware::map_loader
-#endif // MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_
+#endif // AUTOWARE__MAP_LOADER__LANELET2_MAP_LOADER_NODE_HPP_
diff --git a/map/autoware_map_loader/launch/lanelet2_map_loader.launch.xml b/map/autoware_map_loader/launch/lanelet2_map_loader.launch.xml
new file mode 100644
index 0000000000000..48f92550fe404
--- /dev/null
+++ b/map/autoware_map_loader/launch/lanelet2_map_loader.launch.xml
@@ -0,0 +1,15 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/map/map_loader/launch/pointcloud_map_loader.launch.xml b/map/autoware_map_loader/launch/pointcloud_map_loader.launch.xml
similarity index 73%
rename from map/map_loader/launch/pointcloud_map_loader.launch.xml
rename to map/autoware_map_loader/launch/pointcloud_map_loader.launch.xml
index 3633a8fa39a6b..314b3082efff8 100644
--- a/map/map_loader/launch/pointcloud_map_loader.launch.xml
+++ b/map/autoware_map_loader/launch/pointcloud_map_loader.launch.xml
@@ -1,9 +1,9 @@
-
+
-
+
diff --git a/map/map_loader/package.xml b/map/autoware_map_loader/package.xml
similarity index 94%
rename from map/map_loader/package.xml
rename to map/autoware_map_loader/package.xml
index 54cfdcb2b07d3..15fc9fd13df64 100644
--- a/map/map_loader/package.xml
+++ b/map/autoware_map_loader/package.xml
@@ -1,9 +1,9 @@
- map_loader
+ autoware_map_loader
0.38.0
- The map_loader package
+ The autoware_map_loader package
Yamato Ando
Ryu Yamamoto
Masahiro Sakamoto
diff --git a/map/map_loader/schema/lanelet2_map_loader.schema.json b/map/autoware_map_loader/schema/lanelet2_map_loader.schema.json
similarity index 100%
rename from map/map_loader/schema/lanelet2_map_loader.schema.json
rename to map/autoware_map_loader/schema/lanelet2_map_loader.schema.json
diff --git a/map/map_loader/schema/pointcloud_map_loader.schema.json b/map/autoware_map_loader/schema/pointcloud_map_loader.schema.json
similarity index 100%
rename from map/map_loader/schema/pointcloud_map_loader.schema.json
rename to map/autoware_map_loader/schema/pointcloud_map_loader.schema.json
diff --git a/map/map_loader/script/map_hash_generator b/map/autoware_map_loader/script/map_hash_generator
similarity index 100%
rename from map/map_loader/script/map_hash_generator
rename to map/autoware_map_loader/script/map_hash_generator
diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_local_projector.hpp b/map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_local_projector.hpp
similarity index 64%
rename from map/map_loader/src/lanelet2_map_loader/lanelet2_local_projector.hpp
rename to map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_local_projector.hpp
index d73ec0d1ee06e..66b0231c01fd4 100644
--- a/map/map_loader/src/lanelet2_map_loader/lanelet2_local_projector.hpp
+++ b/map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_local_projector.hpp
@@ -17,25 +17,24 @@
#include
-namespace lanelet::projection
+namespace autoware::map_loader
{
-class LocalProjector : public Projector
+class LocalProjector : public lanelet::Projector
{
public:
- LocalProjector() : Projector(Origin(GPSPoint{})) {}
+ LocalProjector() : Projector(lanelet::Origin(lanelet::GPSPoint{})) {}
- BasicPoint3d forward(const GPSPoint & gps) const override // NOLINT
+ lanelet::BasicPoint3d forward(const lanelet::GPSPoint & gps) const override // NOLINT
{
- return BasicPoint3d{0.0, 0.0, gps.ele};
+ return lanelet::BasicPoint3d{0.0, 0.0, gps.ele};
}
- [[nodiscard]] GPSPoint reverse(const BasicPoint3d & point) const override
+ [[nodiscard]] lanelet::GPSPoint reverse(const lanelet::BasicPoint3d & point) const override
{
- return GPSPoint{0.0, 0.0, point.z()};
+ return lanelet::GPSPoint{0.0, 0.0, point.z()};
}
};
-
-} // namespace lanelet::projection
+} // namespace autoware::map_loader
#endif // LANELET2_MAP_LOADER__LANELET2_LOCAL_PROJECTOR_HPP_
diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp b/map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp
similarity index 96%
rename from map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp
rename to map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp
index c2334d4589f27..ee1cc4a58a1be 100644
--- a/map/map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp
+++ b/map/autoware_map_loader/src/lanelet2_map_loader/lanelet2_map_loader_node.cpp
@@ -31,7 +31,7 @@
*
*/
-#include "map_loader/lanelet2_map_loader_node.hpp"
+#include "autoware/map_loader/lanelet2_map_loader_node.hpp"
#include "lanelet2_local_projector.hpp"
@@ -52,6 +52,8 @@
#include
#include
+namespace autoware::map_loader
+{
using autoware_map_msgs::msg::LaneletMapBin;
using tier4_map_msgs::msg::MapProjectorInfo;
@@ -145,7 +147,7 @@ lanelet::LaneletMapPtr Lanelet2MapLoaderNode::load_map(
return map;
}
} else {
- const lanelet::projection::LocalProjector projector;
+ const autoware::map_loader::LocalProjector projector;
lanelet::LaneletMapPtr map = lanelet::load(lanelet2_filename, projector, &errors);
if (!errors.empty()) {
@@ -199,6 +201,7 @@ LaneletMapBin Lanelet2MapLoaderNode::create_map_bin_msg(
return map_bin_msg;
}
+} // namespace autoware::map_loader
#include
-RCLCPP_COMPONENTS_REGISTER_NODE(Lanelet2MapLoaderNode)
+RCLCPP_COMPONENTS_REGISTER_NODE(autoware::map_loader::Lanelet2MapLoaderNode)
diff --git a/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp b/map/autoware_map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp
similarity index 98%
rename from map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp
rename to map/autoware_map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp
index da42389dcc69f..160c6f876138d 100644
--- a/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp
+++ b/map/autoware_map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp
@@ -16,6 +16,8 @@
#include
+namespace autoware::map_loader
+{
DifferentialMapLoaderModule::DifferentialMapLoaderModule(
rclcpp::Node * node, std::map pcd_file_metadata_dict)
: logger_(node->get_logger()), all_pcd_file_metadata_dict_(std::move(pcd_file_metadata_dict))
@@ -89,3 +91,4 @@ DifferentialMapLoaderModule::load_point_cloud_map_cell_with_id(
pointcloud_map_cell_with_id.cell_id = map_id;
return pointcloud_map_cell_with_id;
}
+} // namespace autoware::map_loader
diff --git a/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.hpp b/map/autoware_map_loader/src/pointcloud_map_loader/differential_map_loader_module.hpp
similarity index 96%
rename from map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.hpp
rename to map/autoware_map_loader/src/pointcloud_map_loader/differential_map_loader_module.hpp
index 690ffeca653c8..5c51e7f6206d6 100644
--- a/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.hpp
+++ b/map/autoware_map_loader/src/pointcloud_map_loader/differential_map_loader_module.hpp
@@ -32,6 +32,8 @@
#include
#include
+namespace autoware::map_loader
+{
class DifferentialMapLoaderModule
{
using GetDifferentialPointCloudMap = autoware_map_msgs::srv::GetDifferentialPointCloudMap;
@@ -55,5 +57,6 @@ class DifferentialMapLoaderModule
[[nodiscard]] autoware_map_msgs::msg::PointCloudMapCellWithID load_point_cloud_map_cell_with_id(
const std::string & path, const std::string & map_id) const;
};
+} // namespace autoware::map_loader
#endif // POINTCLOUD_MAP_LOADER__DIFFERENTIAL_MAP_LOADER_MODULE_HPP_
diff --git a/map/map_loader/src/pointcloud_map_loader/partial_map_loader_module.cpp b/map/autoware_map_loader/src/pointcloud_map_loader/partial_map_loader_module.cpp
similarity index 97%
rename from map/map_loader/src/pointcloud_map_loader/partial_map_loader_module.cpp
rename to map/autoware_map_loader/src/pointcloud_map_loader/partial_map_loader_module.cpp
index 62e165dd1005b..afa3da7b82b2d 100644
--- a/map/map_loader/src/pointcloud_map_loader/partial_map_loader_module.cpp
+++ b/map/autoware_map_loader/src/pointcloud_map_loader/partial_map_loader_module.cpp
@@ -16,6 +16,8 @@
#include
+namespace autoware::map_loader
+{
PartialMapLoaderModule::PartialMapLoaderModule(
rclcpp::Node * node, std::map pcd_file_metadata_dict)
: logger_(node->get_logger()), all_pcd_file_metadata_dict_(std::move(pcd_file_metadata_dict))
@@ -76,3 +78,4 @@ PartialMapLoaderModule::load_point_cloud_map_cell_with_id(
pointcloud_map_cell_with_id.cell_id = map_id;
return pointcloud_map_cell_with_id;
}
+} // namespace autoware::map_loader
diff --git a/map/map_loader/src/pointcloud_map_loader/partial_map_loader_module.hpp b/map/autoware_map_loader/src/pointcloud_map_loader/partial_map_loader_module.hpp
similarity index 96%
rename from map/map_loader/src/pointcloud_map_loader/partial_map_loader_module.hpp
rename to map/autoware_map_loader/src/pointcloud_map_loader/partial_map_loader_module.hpp
index ec97661366419..6660c56ade759 100644
--- a/map/map_loader/src/pointcloud_map_loader/partial_map_loader_module.hpp
+++ b/map/autoware_map_loader/src/pointcloud_map_loader/partial_map_loader_module.hpp
@@ -32,6 +32,8 @@
#include
#include
+namespace autoware::map_loader
+{
class PartialMapLoaderModule
{
using GetPartialPointCloudMap = autoware_map_msgs::srv::GetPartialPointCloudMap;
@@ -55,5 +57,6 @@ class PartialMapLoaderModule
[[nodiscard]] autoware_map_msgs::msg::PointCloudMapCellWithID load_point_cloud_map_cell_with_id(
const std::string & path, const std::string & map_id) const;
};
+} // namespace autoware::map_loader
#endif // POINTCLOUD_MAP_LOADER__PARTIAL_MAP_LOADER_MODULE_HPP_
diff --git a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.cpp b/map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.cpp
similarity index 97%
rename from map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.cpp
rename to map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.cpp
index 1754d0b7629a2..0b6521f69ca09 100644
--- a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.cpp
+++ b/map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.cpp
@@ -21,6 +21,8 @@
#include
#include
+namespace autoware::map_loader
+{
sensor_msgs::msg::PointCloud2 downsample(
const sensor_msgs::msg::PointCloud2 & msg_input, const float leaf_size)
{
@@ -99,3 +101,4 @@ sensor_msgs::msg::PointCloud2 PointcloudMapLoaderModule::load_pcd_files(
return whole_pcd;
}
+} // namespace autoware::map_loader
diff --git a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.hpp b/map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.hpp
similarity index 95%
rename from map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.hpp
rename to map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.hpp
index 44f23ded70e37..59145265ecdb4 100644
--- a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.hpp
+++ b/map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.hpp
@@ -28,6 +28,8 @@
#include
#include
+namespace autoware::map_loader
+{
class PointcloudMapLoaderModule
{
public:
@@ -42,5 +44,6 @@ class PointcloudMapLoaderModule
[[nodiscard]] sensor_msgs::msg::PointCloud2 load_pcd_files(
const std::vector & pcd_paths, const boost::optional leaf_size) const;
};
+} // namespace autoware::map_loader
#endif // POINTCLOUD_MAP_LOADER__POINTCLOUD_MAP_LOADER_MODULE_HPP_
diff --git a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp b/map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp
similarity index 97%
rename from map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp
rename to map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp
index c718b25c56694..2500d96650ae3 100644
--- a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp
+++ b/map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp
@@ -24,6 +24,8 @@
#include
#include
+namespace autoware::map_loader
+{
namespace fs = std::filesystem;
namespace
@@ -145,6 +147,7 @@ std::vector PointCloudMapLoaderNode::get_pcd_paths(
}
return pcd_paths;
}
+} // namespace autoware::map_loader
#include
-RCLCPP_COMPONENTS_REGISTER_NODE(PointCloudMapLoaderNode)
+RCLCPP_COMPONENTS_REGISTER_NODE(autoware::map_loader::PointCloudMapLoaderNode)
diff --git a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.hpp b/map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.hpp
similarity index 96%
rename from map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.hpp
rename to map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.hpp
index dbc0d584d347b..251575d7d6424 100644
--- a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.hpp
+++ b/map/autoware_map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.hpp
@@ -33,6 +33,8 @@
#include
#include
+namespace autoware::map_loader
+{
class PointCloudMapLoaderNode : public rclcpp::Node
{
public:
@@ -50,5 +52,6 @@ class PointCloudMapLoaderNode : public rclcpp::Node
std::map get_pcd_metadata(
const std::string & pcd_metadata_path, const std::vector & pcd_paths) const;
};
+} // namespace autoware::map_loader
#endif // POINTCLOUD_MAP_LOADER__POINTCLOUD_MAP_LOADER_NODE_HPP_
diff --git a/map/map_loader/src/pointcloud_map_loader/selected_map_loader_module.cpp b/map/autoware_map_loader/src/pointcloud_map_loader/selected_map_loader_module.cpp
similarity index 98%
rename from map/map_loader/src/pointcloud_map_loader/selected_map_loader_module.cpp
rename to map/autoware_map_loader/src/pointcloud_map_loader/selected_map_loader_module.cpp
index 76b56341b8632..082d1f545dc14 100644
--- a/map/map_loader/src/pointcloud_map_loader/selected_map_loader_module.cpp
+++ b/map/autoware_map_loader/src/pointcloud_map_loader/selected_map_loader_module.cpp
@@ -15,7 +15,8 @@
#include "selected_map_loader_module.hpp"
#include
-namespace
+
+namespace autoware::map_loader
{
autoware_map_msgs::msg::PointCloudMapMetaData create_metadata(
const std::map & pcd_file_metadata_dict)
@@ -42,7 +43,6 @@ autoware_map_msgs::msg::PointCloudMapMetaData create_metadata(
return metadata_msg;
}
-} // namespace
SelectedMapLoaderModule::SelectedMapLoaderModule(
rclcpp::Node * node, std::map pcd_file_metadata_dict)
@@ -107,3 +107,4 @@ SelectedMapLoaderModule::load_point_cloud_map_cell_with_id(
pointcloud_map_cell_with_id.cell_id = map_id;
return pointcloud_map_cell_with_id;
}
+} // namespace autoware::map_loader
diff --git a/map/map_loader/src/pointcloud_map_loader/selected_map_loader_module.hpp b/map/autoware_map_loader/src/pointcloud_map_loader/selected_map_loader_module.hpp
similarity index 96%
rename from map/map_loader/src/pointcloud_map_loader/selected_map_loader_module.hpp
rename to map/autoware_map_loader/src/pointcloud_map_loader/selected_map_loader_module.hpp
index eea8b8c1950ae..bc07543d7a6be 100644
--- a/map/map_loader/src/pointcloud_map_loader/selected_map_loader_module.hpp
+++ b/map/autoware_map_loader/src/pointcloud_map_loader/selected_map_loader_module.hpp
@@ -33,6 +33,8 @@
#include
#include
+namespace autoware::map_loader
+{
class SelectedMapLoaderModule
{
using GetSelectedPointCloudMap = autoware_map_msgs::srv::GetSelectedPointCloudMap;
@@ -55,5 +57,6 @@ class SelectedMapLoaderModule
[[nodiscard]] autoware_map_msgs::msg::PointCloudMapCellWithID load_point_cloud_map_cell_with_id(
const std::string & path, const std::string & map_id) const;
};
+} // namespace autoware::map_loader
#endif // POINTCLOUD_MAP_LOADER__SELECTED_MAP_LOADER_MODULE_HPP_
diff --git a/map/map_loader/src/pointcloud_map_loader/utils.cpp b/map/autoware_map_loader/src/pointcloud_map_loader/utils.cpp
similarity index 98%
rename from map/map_loader/src/pointcloud_map_loader/utils.cpp
rename to map/autoware_map_loader/src/pointcloud_map_loader/utils.cpp
index ea2c2e7033014..172d462947548 100644
--- a/map/map_loader/src/pointcloud_map_loader/utils.cpp
+++ b/map/autoware_map_loader/src/pointcloud_map_loader/utils.cpp
@@ -20,6 +20,8 @@
#include
#include
+namespace autoware::map_loader
+{
std::map load_pcd_metadata(const std::string & pcd_metadata_path)
{
YAML::Node config = YAML::LoadFile(pcd_metadata_path);
@@ -107,3 +109,4 @@ bool is_grid_within_queried_area(
cylinder_and_box_overlap_exists(center_x, center_y, radius, metadata.min, metadata.max);
return res;
}
+} // namespace autoware::map_loader
diff --git a/map/map_loader/src/pointcloud_map_loader/utils.hpp b/map/autoware_map_loader/src/pointcloud_map_loader/utils.hpp
similarity index 96%
rename from map/map_loader/src/pointcloud_map_loader/utils.hpp
rename to map/autoware_map_loader/src/pointcloud_map_loader/utils.hpp
index 07e8ade5c6f7c..7a3cec7fcc14a 100644
--- a/map/map_loader/src/pointcloud_map_loader/utils.hpp
+++ b/map/autoware_map_loader/src/pointcloud_map_loader/utils.hpp
@@ -26,6 +26,8 @@
#include
#include
+namespace autoware::map_loader
+{
struct PCDFileMetadata
{
pcl::PointXYZ min;
@@ -48,4 +50,6 @@ bool cylinder_and_box_overlap_exists(
bool is_grid_within_queried_area(
const autoware_map_msgs::msg::AreaInfo area, const PCDFileMetadata metadata);
+} // namespace autoware::map_loader
+
#endif // POINTCLOUD_MAP_LOADER__UTILS_HPP_
diff --git a/map/map_loader/test/data/test_map.osm b/map/autoware_map_loader/test/data/test_map.osm
similarity index 100%
rename from map/map_loader/test/data/test_map.osm
rename to map/autoware_map_loader/test/data/test_map.osm
diff --git a/map/map_loader/test/lanelet2_map_loader_launch.test.py b/map/autoware_map_loader/test/lanelet2_map_loader_launch.test.py
similarity index 91%
rename from map/map_loader/test/lanelet2_map_loader_launch.test.py
rename to map/autoware_map_loader/test/lanelet2_map_loader_launch.test.py
index 0a29a74e90b06..14f05b1938b61 100644
--- a/map/map_loader/test/lanelet2_map_loader_launch.test.py
+++ b/map/autoware_map_loader/test/lanelet2_map_loader_launch.test.py
@@ -28,12 +28,12 @@
@pytest.mark.launch_test
def generate_test_description():
lanelet2_map_path = os.path.join(
- get_package_share_directory("map_loader"), "test/data/test_map.osm"
+ get_package_share_directory("autoware_map_loader"), "test/data/test_map.osm"
)
lanelet2_map_loader = Node(
- package="map_loader",
- executable="lanelet2_map_loader",
+ package="autoware_map_loader",
+ executable="autoware_lanelet2_map_loader",
parameters=[
{
"lanelet2_map_path": lanelet2_map_path,
diff --git a/map/map_loader/test/test_cylinder_box_overlap.cpp b/map/autoware_map_loader/test/test_cylinder_box_overlap.cpp
similarity index 97%
rename from map/map_loader/test/test_cylinder_box_overlap.cpp
rename to map/autoware_map_loader/test/test_cylinder_box_overlap.cpp
index d8ca2ca9f8734..6ab0c0a309be0 100644
--- a/map/map_loader/test/test_cylinder_box_overlap.cpp
+++ b/map/autoware_map_loader/test/test_cylinder_box_overlap.cpp
@@ -16,6 +16,8 @@
#include
+using autoware::map_loader::cylinder_and_box_overlap_exists;
+
TEST(CylinderAndBoxOverlapExists, NoOverlap)
{
// Cylinder: center = (5, 0), radius = 4 - 0.1
diff --git a/map/map_loader/test/test_differential_map_loader_module.cpp b/map/autoware_map_loader/test/test_differential_map_loader_module.cpp
similarity index 94%
rename from map/map_loader/test/test_differential_map_loader_module.cpp
rename to map/autoware_map_loader/test/test_differential_map_loader_module.cpp
index e25a8f97a70ca..cd9b670b32fd3 100644
--- a/map/map_loader/test/test_differential_map_loader_module.cpp
+++ b/map/autoware_map_loader/test/test_differential_map_loader_module.cpp
@@ -23,6 +23,7 @@
#include
+using autoware::map_loader::DifferentialMapLoaderModule;
using autoware_map_msgs::srv::GetDifferentialPointCloudMap;
class TestDifferentialMapLoaderModule : public ::testing::Test
@@ -45,8 +46,8 @@ class TestDifferentialMapLoaderModule : public ::testing::Test
pcl::io::savePCDFileASCII("/tmp/dummy.pcd", dummy_cloud);
// Generate a sample dummy pointcloud metadata dictionary
- std::map dummy_metadata_dict;
- PCDFileMetadata dummy_metadata;
+ std::map dummy_metadata_dict;
+ autoware::map_loader::PCDFileMetadata dummy_metadata;
dummy_metadata.min = pcl::PointXYZ(-1.0, -1.0, -1.0);
dummy_metadata.max = pcl::PointXYZ(1.0, 1.0, 1.0);
dummy_metadata_dict["/tmp/dummy.pcd"] = dummy_metadata;
diff --git a/map/map_loader/test/test_load_pcd_metadata.cpp b/map/autoware_map_loader/test/test_load_pcd_metadata.cpp
similarity index 90%
rename from map/map_loader/test/test_load_pcd_metadata.cpp
rename to map/autoware_map_loader/test/test_load_pcd_metadata.cpp
index fcec100f389c5..dc23c3a9fb2d6 100644
--- a/map/map_loader/test/test_load_pcd_metadata.cpp
+++ b/map/autoware_map_loader/test/test_load_pcd_metadata.cpp
@@ -39,12 +39,12 @@ TEST(LoadPCDMetadataTest, BasicFunctionality)
{
std::string yaml_file_path = create_yaml_file();
- std::map expected = {
+ std::map expected = {
{"file1.pcd", {{1, 2, 0}, {6, 8, 0}}},
{"file2.pcd", {{3, 4, 0}, {8, 10, 0}}},
};
- auto result = load_pcd_metadata(yaml_file_path);
+ auto result = autoware::map_loader::load_pcd_metadata(yaml_file_path);
ASSERT_THAT(result, ContainerEq(expected));
}
diff --git a/map/map_loader/test/test_partial_map_loader_module.cpp b/map/autoware_map_loader/test/test_partial_map_loader_module.cpp
similarity index 94%
rename from map/map_loader/test/test_partial_map_loader_module.cpp
rename to map/autoware_map_loader/test/test_partial_map_loader_module.cpp
index 9ff27df29ab8b..fd25b600c81af 100644
--- a/map/map_loader/test/test_partial_map_loader_module.cpp
+++ b/map/autoware_map_loader/test/test_partial_map_loader_module.cpp
@@ -22,6 +22,7 @@
#include
+using autoware::map_loader::PartialMapLoaderModule;
using autoware_map_msgs::srv::GetPartialPointCloudMap;
class TestPartialMapLoaderModule : public ::testing::Test
@@ -44,8 +45,8 @@ class TestPartialMapLoaderModule : public ::testing::Test
pcl::io::savePCDFileASCII("/tmp/dummy.pcd", dummy_cloud);
// Generate a sample dummy pointcloud metadata dictionary
- std::map dummy_metadata_dict;
- PCDFileMetadata dummy_metadata;
+ std::map dummy_metadata_dict;
+ autoware::map_loader::PCDFileMetadata dummy_metadata;
dummy_metadata.min = pcl::PointXYZ(-1.0, -1.0, -1.0);
dummy_metadata.max = pcl::PointXYZ(1.0, 1.0, 1.0);
dummy_metadata_dict["/tmp/dummy.pcd"] = dummy_metadata;
diff --git a/map/map_loader/test/test_pointcloud_map_loader_module.cpp b/map/autoware_map_loader/test/test_pointcloud_map_loader_module.cpp
similarity index 96%
rename from map/map_loader/test/test_pointcloud_map_loader_module.cpp
rename to map/autoware_map_loader/test/test_pointcloud_map_loader_module.cpp
index 5667f476b4dab..d61839d5abfc8 100644
--- a/map/map_loader/test/test_pointcloud_map_loader_module.cpp
+++ b/map/autoware_map_loader/test/test_pointcloud_map_loader_module.cpp
@@ -65,7 +65,8 @@ TEST_F(TestPointcloudMapLoaderModule, LoadPCDFilesNoDownsampleTest)
std::vector pcd_paths = {temp_pcd_path};
// Create PointcloudMapLoaderModule instance
- PointcloudMapLoaderModule loader(node.get(), pcd_paths, "pointcloud_map_no_downsample", false);
+ autoware::map_loader::PointcloudMapLoaderModule loader(
+ node.get(), pcd_paths, "pointcloud_map_no_downsample", false);
// Create a subscriber to the published pointcloud topic
auto pointcloud_received = std::make_shared(false);
diff --git a/map/map_loader/test/test_replace_with_absolute_path.cpp b/map/autoware_map_loader/test/test_replace_with_absolute_path.cpp
similarity index 95%
rename from map/map_loader/test/test_replace_with_absolute_path.cpp
rename to map/autoware_map_loader/test/test_replace_with_absolute_path.cpp
index 03d533d41cf18..e8ccfbd5fb9f4 100644
--- a/map/map_loader/test/test_replace_with_absolute_path.cpp
+++ b/map/autoware_map_loader/test/test_replace_with_absolute_path.cpp
@@ -17,6 +17,8 @@
#include
#include
+using autoware::map_loader::PCDFileMetadata;
+using autoware::map_loader::replace_with_absolute_path;
using ::testing::ContainerEq;
TEST(ReplaceWithAbsolutePathTest, BasicFunctionality)
diff --git a/map/autoware_map_projection_loader/README.md b/map/autoware_map_projection_loader/README.md
index 11246c092231e..2568bb2c17df7 100644
--- a/map/autoware_map_projection_loader/README.md
+++ b/map/autoware_map_projection_loader/README.md
@@ -11,7 +11,7 @@ This is necessary information especially when you want to convert from global (g
## Map projector info file specification
-You need to provide a YAML file, namely `map_projector_info.yaml` under the `map_path` directory. For `pointcloud_map_metadata.yaml`, please refer to the Readme of `map_loader`.
+You need to provide a YAML file, namely `map_projector_info.yaml` under the `map_path` directory. For `pointcloud_map_metadata.yaml`, please refer to the Readme of `autoware_map_loader`.
```bash
sample-map-rosbag
diff --git a/map/map_loader/launch/lanelet2_map_loader.launch.xml b/map/map_loader/launch/lanelet2_map_loader.launch.xml
deleted file mode 100644
index 5baee911d6572..0000000000000
--- a/map/map_loader/launch/lanelet2_map_loader.launch.xml
+++ /dev/null
@@ -1,20 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml b/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml
index 38379a52e4c92..b897cf4d88711 100644
--- a/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml
+++ b/planning/autoware_static_centerline_generator/launch/static_centerline_generator.launch.xml
@@ -20,7 +20,7 @@
-
+
autoware_geography_utils
autoware_interpolation
autoware_lanelet2_extension
+ autoware_map_loader
autoware_map_msgs
autoware_map_projection_loader
autoware_mission_planner
@@ -33,7 +34,6 @@
autoware_vehicle_info_utils
geometry_msgs
global_parameter_loader
- map_loader
rclcpp
rclcpp_components
tier4_map_msgs
diff --git a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp
index a6ba007e71485..398edc215da3e 100644
--- a/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp
+++ b/planning/autoware_static_centerline_generator/src/static_centerline_generator_node.cpp
@@ -15,6 +15,7 @@
#include "static_centerline_generator_node.hpp"
#include "autoware/interpolation/spline_interpolation_points_2d.hpp"
+#include "autoware/map_loader/lanelet2_map_loader_node.hpp"
#include "autoware/map_projection_loader/load_info_from_lanelet2_map.hpp"
#include "autoware/map_projection_loader/map_projection_loader.hpp"
#include "autoware/motion_utils/resample/resample.hpp"
@@ -26,7 +27,6 @@
#include "autoware_lanelet2_extension/utility/utilities.hpp"
#include "autoware_static_centerline_generator/msg/points_with_lane_id.hpp"
#include "centerline_source/bag_ego_trajectory_based_centerline.hpp"
-#include "map_loader/lanelet2_map_loader_node.hpp"
#include "type_alias.hpp"
#include "utils.hpp"
@@ -358,24 +358,24 @@ void StaticCenterlineGeneratorNode::load_map(const std::string & lanelet2_input_
// load map
map_projector_info_ = std::make_unique(
autoware::map_projection_loader::load_info_from_lanelet2_map(lanelet2_input_file_path));
- const auto map_ptr =
- Lanelet2MapLoaderNode::load_map(lanelet2_input_file_path, *map_projector_info_);
+ const auto map_ptr = autoware::map_loader::Lanelet2MapLoaderNode::load_map(
+ lanelet2_input_file_path, *map_projector_info_);
if (!map_ptr) {
return nullptr;
}
// NOTE: The original map is stored here since the centerline will be added to all the
// lanelet when lanelet::utils::overwriteLaneletCenterline is called.
- original_map_ptr_ =
- Lanelet2MapLoaderNode::load_map(lanelet2_input_file_path, *map_projector_info_);
+ original_map_ptr_ = autoware::map_loader::Lanelet2MapLoaderNode::load_map(
+ lanelet2_input_file_path, *map_projector_info_);
// overwrite more dense centerline
// NOTE: overwriteLaneletsCenterlineWithWaypoints is used only in real time calculation.
lanelet::utils::overwriteLaneletsCenterline(map_ptr, 5.0, false);
// create map bin msg
- const auto map_bin_msg =
- Lanelet2MapLoaderNode::create_map_bin_msg(map_ptr, lanelet2_input_file_path, now());
+ const auto map_bin_msg = autoware::map_loader::Lanelet2MapLoaderNode::create_map_bin_msg(
+ map_ptr, lanelet2_input_file_path, now());
return std::make_shared(map_bin_msg);
}();
diff --git a/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py b/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py
index 4bb0630d13942..ca2621212ef83 100644
--- a/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py
+++ b/planning/autoware_static_centerline_generator/test/test_static_centerline_generator.test.py
@@ -71,7 +71,7 @@ def generate_test_description():
"config/path_optimizer.param.yaml",
),
os.path.join(
- get_package_share_directory("map_loader"),
+ get_package_share_directory("autoware_map_loader"),
"config/lanelet2_map_loader.param.yaml",
),
os.path.join(