From 98e2f20ef40fba28dc1039d64d3f7829a939771c Mon Sep 17 00:00:00 2001 From: Shintaro Sakoda Date: Tue, 30 Jan 2024 14:07:52 +0900 Subject: [PATCH] Changed error handling when pcd_metadata file not found Signed-off-by: Shintaro Sakoda --- .../src/pointcloud_map_loader/pointcloud_map_loader_node.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 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 5f4b3e311e6e9..d7bd75a1e9f90 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,8 +90,9 @@ std::map PointCloudMapLoaderNode::getPCDMetadata( { std::map pcd_metadata_dict; if (pcd_paths.size() != 1) { - if (!fs::exists(pcd_metadata_path)) { - throw std::runtime_error("PCD metadata file not found: " + pcd_metadata_path); + 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)); } pcd_metadata_dict = loadPCDMetadata(pcd_metadata_path);