diff --git a/common/component_interface_specs/package.xml b/common/component_interface_specs/package.xml
index c8ca0dd0627e5..fdaf816d03736 100644
--- a/common/component_interface_specs/package.xml
+++ b/common/component_interface_specs/package.xml
@@ -15,8 +15,8 @@
autoware_auto_perception_msgs
autoware_auto_planning_msgs
autoware_auto_vehicle_msgs
- autoware_planning_msgs
autoware_map_msgs
+ autoware_planning_msgs
nav_msgs
rcl
rclcpp
diff --git a/map/autoware_dynamic_lanelet_provider/CMakeLists.txt b/map/autoware_dynamic_lanelet_provider/CMakeLists.txt
index 44761379aee73..aa25a9e2430d5 100644
--- a/map/autoware_dynamic_lanelet_provider/CMakeLists.txt
+++ b/map/autoware_dynamic_lanelet_provider/CMakeLists.txt
@@ -16,4 +16,4 @@ rclcpp_components_register_node(dynamic_lanelet_provider_node
ament_auto_package(INSTALL_TO_SHARE
launch
config
-)
\ No newline at end of file
+)
diff --git a/map/autoware_dynamic_lanelet_provider/config/dynamic_lanelet_provider.param.yaml b/map/autoware_dynamic_lanelet_provider/config/dynamic_lanelet_provider.param.yaml
index 36d82b6737030..d1becd22634e2 100644
--- a/map/autoware_dynamic_lanelet_provider/config/dynamic_lanelet_provider.param.yaml
+++ b/map/autoware_dynamic_lanelet_provider/config/dynamic_lanelet_provider.param.yaml
@@ -2,4 +2,4 @@
ros__parameters:
dynamic_map_loading_grid_size: 50.0 # [m]
dynamic_map_loading_update_distance: 100.0 # [m]
- dynamic_map_loading_map_radius: 150.0 # [m]
\ No newline at end of file
+ dynamic_map_loading_map_radius: 150.0 # [m]
diff --git a/map/autoware_dynamic_lanelet_provider/include/autoware/dynamic_lanelet_provider/dynamic_lanelet_provider.hpp b/map/autoware_dynamic_lanelet_provider/include/autoware/dynamic_lanelet_provider/dynamic_lanelet_provider.hpp
index 5f97f4c966010..87dd8ebad22f8 100644
--- a/map/autoware_dynamic_lanelet_provider/include/autoware/dynamic_lanelet_provider/dynamic_lanelet_provider.hpp
+++ b/map/autoware_dynamic_lanelet_provider/include/autoware/dynamic_lanelet_provider/dynamic_lanelet_provider.hpp
@@ -1,7 +1,7 @@
-#ifndef AUTOWARE_DYNAMIC_LANELET_PROVIDER_HPP
-#define AUTOWARE_DYNAMIC_LANELET_PROVIDER_HPP
+#ifndef AUTOWARE__DYNAMIC_LANELET_PROVIDER__DYNAMIC_LANELET_PROVIDER_HPP_
+#define AUTOWARE__DYNAMIC_LANELET_PROVIDER__DYNAMIC_LANELET_PROVIDER_HPP_
#include
#include
@@ -74,4 +74,4 @@ class DynamicLaneletProviderNode : public rclcpp::Node
} // namespace dynamic_lanelet_provider
} // namespace autoware
-#endif // AUTOWARE_DYNAMIC_LANELET_PROVIDER_HPP
+#endif // AUTOWARE__DYNAMIC_LANELET_PROVIDER__DYNAMIC_LANELET_PROVIDER_HPP_
diff --git a/map/autoware_dynamic_lanelet_provider/launch/dynamic_lanelet_provider.launch.xml b/map/autoware_dynamic_lanelet_provider/launch/dynamic_lanelet_provider.launch.xml
index 02d326071997d..ea8cd938a245b 100644
--- a/map/autoware_dynamic_lanelet_provider/launch/dynamic_lanelet_provider.launch.xml
+++ b/map/autoware_dynamic_lanelet_provider/launch/dynamic_lanelet_provider.launch.xml
@@ -1,8 +1,7 @@
-
+
-
-
-
-
-
\ No newline at end of file
+
+
+
+
diff --git a/map/autoware_dynamic_lanelet_provider/package.xml b/map/autoware_dynamic_lanelet_provider/package.xml
index 210918dbefd1e..5af857213dce4 100644
--- a/map/autoware_dynamic_lanelet_provider/package.xml
+++ b/map/autoware_dynamic_lanelet_provider/package.xml
@@ -10,10 +10,10 @@
ament_cmake_auto
autoware_cmake
- component_interface_specs
- component_interface_utils
autoware_auto_mapping_msgs
autoware_map_msgs
+ component_interface_specs
+ component_interface_utils
geography_utils
diff --git a/map/autoware_dynamic_lanelet_provider/src/dynamic_lanelet_provider.cpp b/map/autoware_dynamic_lanelet_provider/src/dynamic_lanelet_provider.cpp
index 3ffe9e05c19f3..4f1ac10aa518d 100644
--- a/map/autoware_dynamic_lanelet_provider/src/dynamic_lanelet_provider.cpp
+++ b/map/autoware_dynamic_lanelet_provider/src/dynamic_lanelet_provider.cpp
@@ -144,7 +144,8 @@ void DynamicLaneletProviderNode::updateMap(const geometry_msgs::msg::Point & pos
}
auto request = std::make_shared();
- request->vector_map_file_ids.insert(request->vector_map_file_ids.end(), cache_ids.begin(), cache_ids.end());
+ request->vector_map_file_ids.insert(
+ request->vector_map_file_ids.end(), cache_ids.begin(), cache_ids.end());
while (!map_loader_client_->wait_for_service(std::chrono::seconds(1)) && rclcpp::ok()) {
RCLCPP_INFO(get_logger(), "Waiting for lanelet loader service");
@@ -196,4 +197,4 @@ bool DynamicLaneletProviderNode::should_update_map() const
} // namespace autoware
#include
-RCLCPP_COMPONENTS_REGISTER_NODE(autoware::dynamic_lanelet_provider::DynamicLaneletProviderNode)
\ No newline at end of file
+RCLCPP_COMPONENTS_REGISTER_NODE(autoware::dynamic_lanelet_provider::DynamicLaneletProviderNode)
diff --git a/map/map_loader/src/lanelet2_map_loader/lanelet2_differential_loader_module.cpp b/map/map_loader/src/lanelet2_map_loader/lanelet2_differential_loader_module.cpp
index 1ac0c366c7989..5e2b14bda0364 100644
--- a/map/map_loader/src/lanelet2_map_loader/lanelet2_differential_loader_module.cpp
+++ b/map/map_loader/src/lanelet2_map_loader/lanelet2_differential_loader_module.cpp
@@ -136,7 +136,6 @@ Lanelet2DifferentialLoaderModule::getLaneletMapMetaDataMsg() const
tile_msg.origin_lat = file.second.origin_lat;
tile_msg.origin_lon = file.second.origin_lon;
-
metadata.metadata_list.push_back(tile_msg);
}
metadata.header.frame_id = "map";
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 d606a46a63371..90bdc51f7459e 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
@@ -82,7 +82,7 @@ Lanelet2MapLoaderNode::Lanelet2MapLoaderNode(const rclcpp::NodeOptions & options
declare_parameter("lanelet2_map_path");
declare_parameter("center_line_resolution");
-
+
if (declare_parameter("enabled_dynamic_lanelet_loading")) {
std::vector lanelet2_paths_or_directory =
declare_parameter>("lanelet2_map_folder_path");