Skip to content

Commit 25bc636

Browse files
fix(map_loader): change error handling when pcd_metadata file not found (#6227)
Changed error handling when pcd_metadata file not found Signed-off-by: Shintaro Sakoda <shintaro.sakoda@tier4.jp>
1 parent 5e8da39 commit 25bc636

File tree

1 file changed

+3
-2
lines changed

1 file changed

+3
-2
lines changed

map/map_loader/src/pointcloud_map_loader/pointcloud_map_loader_node.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -90,8 +90,9 @@ std::map<std::string, PCDFileMetadata> PointCloudMapLoaderNode::getPCDMetadata(
9090
{
9191
std::map<std::string, PCDFileMetadata> pcd_metadata_dict;
9292
if (pcd_paths.size() != 1) {
93-
if (!fs::exists(pcd_metadata_path)) {
94-
throw std::runtime_error("PCD metadata file not found: " + pcd_metadata_path);
93+
while (!fs::exists(pcd_metadata_path)) {
94+
RCLCPP_ERROR_STREAM(get_logger(), "PCD metadata file not found: " << pcd_metadata_path);
95+
std::this_thread::sleep_for(std::chrono::seconds(1));
9596
}
9697

9798
pcd_metadata_dict = loadPCDMetadata(pcd_metadata_path);

0 commit comments

Comments
 (0)