From e232f22c2abeaf21d9b132e709a48b608b4442e0 Mon Sep 17 00:00:00 2001 From: Shintaro Sakoda <shintaro.sakoda@tier4.jp> Date: Fri, 2 Feb 2024 17:07:24 +0900 Subject: [PATCH] Revert "fix(map_loader): change error handling when pcd_metadata file not found (#6227)" This reverts commit 25bc636fe0f796c63daac60123aa6138146e515d. --- .../src/pointcloud_map_loader/pointcloud_map_loader_node.cpp | 5 ++--- 1 file changed, 2 insertions(+), 3 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 d7bd75a1e9f90..5f4b3e311e6e9 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 @@ -90,9 +90,8 @@ std::map<std::string, PCDFileMetadata> PointCloudMapLoaderNode::getPCDMetadata( { std::map<std::string, PCDFileMetadata> pcd_metadata_dict; if (pcd_paths.size() != 1) { - while (!fs::exists(pcd_metadata_path)) { - RCLCPP_ERROR_STREAM(get_logger(), "PCD metadata file not found: " << pcd_metadata_path); - std::this_thread::sleep_for(std::chrono::seconds(1)); + if (!fs::exists(pcd_metadata_path)) { + throw std::runtime_error("PCD metadata file not found: " + pcd_metadata_path); } pcd_metadata_dict = loadPCDMetadata(pcd_metadata_path);