diff --git a/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp b/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp index b42b919edb59d..8322ac5f60b99 100644 --- a/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp +++ b/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.cpp @@ -26,7 +26,7 @@ DifferentialMapLoaderModule::DifferentialMapLoaderModule( } void DifferentialMapLoaderModule::differentialAreaLoad( - const autoware_map_msgs::msg::AreaInfo area, const std::vector & cached_ids, + const autoware_map_msgs::msg::AreaInfo & area, const std::vector & cached_ids, GetDifferentialPointCloudMap::Response::SharedPtr & response) const { // iterate over all the available pcd map grids @@ -52,7 +52,7 @@ void DifferentialMapLoaderModule::differentialAreaLoad( } } - for (int i = 0; i < static_cast(cached_ids.size()); ++i) { + for (size_t i = 0; i < cached_ids.size(); ++i) { if (should_remove[i]) { response->ids_to_remove.push_back(cached_ids[i]); } @@ -72,7 +72,7 @@ bool DifferentialMapLoaderModule::onServiceGetDifferentialPointCloudMap( autoware_map_msgs::msg::PointCloudMapCellWithID DifferentialMapLoaderModule::loadPointCloudMapCellWithID( - const std::string path, const std::string map_id) const + const std::string & path, const std::string & map_id) const { sensor_msgs::msg::PointCloud2 pcd; if (pcl::io::loadPCDFile(path, pcd) == -1) { diff --git a/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.hpp b/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.hpp index 5d6188c0b1a1f..7069e1dbdf45c 100644 --- a/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.hpp +++ b/map/map_loader/src/pointcloud_map_loader/differential_map_loader_module.hpp @@ -50,10 +50,10 @@ class DifferentialMapLoaderModule GetDifferentialPointCloudMap::Request::SharedPtr req, GetDifferentialPointCloudMap::Response::SharedPtr res); void differentialAreaLoad( - const autoware_map_msgs::msg::AreaInfo area_info, const std::vector & cached_ids, + const autoware_map_msgs::msg::AreaInfo & area_info, const std::vector & cached_ids, GetDifferentialPointCloudMap::Response::SharedPtr & response) const; autoware_map_msgs::msg::PointCloudMapCellWithID loadPointCloudMapCellWithID( - const std::string path, const std::string map_id) const; + const std::string & path, const std::string & map_id) const; }; #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/map_loader/src/pointcloud_map_loader/partial_map_loader_module.cpp index af53438e8e321..1454b01147ac2 100644 --- a/map/map_loader/src/pointcloud_map_loader/partial_map_loader_module.cpp +++ b/map/map_loader/src/pointcloud_map_loader/partial_map_loader_module.cpp @@ -25,7 +25,7 @@ PartialMapLoaderModule::PartialMapLoaderModule( } void PartialMapLoaderModule::partialAreaLoad( - const autoware_map_msgs::msg::AreaInfo area, + const autoware_map_msgs::msg::AreaInfo & area, GetPartialPointCloudMap::Response::SharedPtr & response) const { // iterate over all the available pcd map grids @@ -56,7 +56,7 @@ bool PartialMapLoaderModule::onServiceGetPartialPointCloudMap( } autoware_map_msgs::msg::PointCloudMapCellWithID PartialMapLoaderModule::loadPointCloudMapCellWithID( - const std::string path, const std::string map_id) const + const std::string & path, const std::string & map_id) const { sensor_msgs::msg::PointCloud2 pcd; if (pcl::io::loadPCDFile(path, pcd) == -1) { diff --git a/map/map_loader/src/pointcloud_map_loader/partial_map_loader_module.hpp b/map/map_loader/src/pointcloud_map_loader/partial_map_loader_module.hpp index 052aa4245c099..4d97ab90667ec 100644 --- a/map/map_loader/src/pointcloud_map_loader/partial_map_loader_module.hpp +++ b/map/map_loader/src/pointcloud_map_loader/partial_map_loader_module.hpp @@ -50,10 +50,10 @@ class PartialMapLoaderModule GetPartialPointCloudMap::Request::SharedPtr req, GetPartialPointCloudMap::Response::SharedPtr res); void partialAreaLoad( - const autoware_map_msgs::msg::AreaInfo area, + const autoware_map_msgs::msg::AreaInfo & area, GetPartialPointCloudMap::Response::SharedPtr & response) const; autoware_map_msgs::msg::PointCloudMapCellWithID loadPointCloudMapCellWithID( - const std::string path, const std::string map_id) const; + const std::string & path, const std::string & map_id) const; }; #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/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.cpp index cd1a75fad5a03..1c67d25f08f7a 100644 --- a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.cpp +++ b/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.cpp @@ -40,8 +40,8 @@ sensor_msgs::msg::PointCloud2 downsample( } PointcloudMapLoaderModule::PointcloudMapLoaderModule( - rclcpp::Node * node, const std::vector & pcd_paths, const std::string publisher_name, - const bool use_downsample) + rclcpp::Node * node, const std::vector & pcd_paths, + const std::string & publisher_name, const bool use_downsample) : logger_(node->get_logger()) { rclcpp::QoS durable_qos{1}; @@ -72,12 +72,11 @@ sensor_msgs::msg::PointCloud2 PointcloudMapLoaderModule::loadPCDFiles( sensor_msgs::msg::PointCloud2 whole_pcd; sensor_msgs::msg::PointCloud2 partial_pcd; - for (int i = 0; i < static_cast(pcd_paths.size()); ++i) { + for (size_t i = 0; i < pcd_paths.size(); ++i) { auto & path = pcd_paths[i]; if (i % 50 == 0) { RCLCPP_INFO_STREAM( - logger_, - fmt::format("Load {} ({} out of {})", path, i + 1, static_cast(pcd_paths.size()))); + logger_, fmt::format("Load {} ({} out of {})", path, i + 1, pcd_paths.size())); } if (pcl::io::loadPCDFile(path, partial_pcd) == -1) { diff --git a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.hpp b/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.hpp index 4cd0e981597c6..aebc5a17454ab 100644 --- a/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.hpp +++ b/map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_module.hpp @@ -29,7 +29,7 @@ class PointcloudMapLoaderModule public: explicit PointcloudMapLoaderModule( rclcpp::Node * node, const std::vector & pcd_paths, - const std::string publisher_name, const bool use_downsample); + const std::string & publisher_name, const bool use_downsample); private: rclcpp::Logger logger_;