From 6f3b704c2a959438165cdb15a32eb9ac2d710af9 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 24 Mar 2023 11:38:18 +0000 Subject: [PATCH] style(pre-commit): autofix --- .../pointcloud_map_loader/pointcloud_map_loader_node.cpp | 1 - map/map_loader/src/pointcloud_map_loader/utils.cpp | 7 ++++--- map/map_loader/src/pointcloud_map_loader/utils.hpp | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp b/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp index 0dcd796e463c4..ca0510bd11ce7 100644 --- a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp +++ b/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp @@ -76,7 +76,6 @@ PointCloudMapLoaderNode::PointCloudMapLoaderNode(const rclcpp::NodeOptions & opt pcd_metadata_dict_ = loadPCDMetadata(pcd_metadata_path); pcd_metadata_dict_ = replaceWithAbsolutePath(pcd_metadata_dict_, pcd_paths); RCLCPP_INFO_STREAM(get_logger(), "Loaded PCD metadata: " << pcd_metadata_path); - } if (enable_partial_load) { diff --git a/map/map_loader/src/pointcloud_map_loader/utils.cpp b/map/map_loader/src/pointcloud_map_loader/utils.cpp index d3b3b3b76d6ff..5e66627d50457 100644 --- a/map/map_loader/src/pointcloud_map_loader/utils.cpp +++ b/map/map_loader/src/pointcloud_map_loader/utils.cpp @@ -45,10 +45,11 @@ std::map loadPCDMetadata(const std::string & pcd_m } std::map replaceWithAbsolutePath( - const std::map &pcd_metadata_path, - const std::vector &pcd_paths) { + const std::map & pcd_metadata_path, + const std::vector & pcd_paths) +{ std::map absolute_path_map; - for (const auto &path : pcd_paths) { + for (const auto & path : pcd_paths) { std::string filename = path.substr(path.find_last_of("/\\") + 1); auto it = pcd_metadata_path.find(filename); if (it != pcd_metadata_path.end()) { diff --git a/map/map_loader/src/pointcloud_map_loader/utils.hpp b/map/map_loader/src/pointcloud_map_loader/utils.hpp index 6be2f5a90cea9..163435d1120eb 100644 --- a/map/map_loader/src/pointcloud_map_loader/utils.hpp +++ b/map/map_loader/src/pointcloud_map_loader/utils.hpp @@ -29,8 +29,8 @@ struct PCDFileMetadata std::map loadPCDMetadata(const std::string & pcd_metadata_path); std::map replaceWithAbsolutePath( - const std::map &pcd_metadata_path, - const std::vector &pcd_paths); + const std::map & pcd_metadata_path, + const std::vector & pcd_paths); bool sphereAndBoxOverlapExists( const geometry_msgs::msg::Point position, const double radius, const pcl::PointXYZ position_min,