Skip to content

Commit

Permalink
revert(map_loader): revert the change error handling when pcd_metadat…
Browse files Browse the repository at this point in the history
…a file (#6294)

Revert "fix(map_loader): change error handling when pcd_metadata file not found (#6227)"

This reverts commit 25bc636.
  • Loading branch information
SakodaShintaro authored Feb 2, 2024
1 parent fa8424d commit e063f2d
Showing 1 changed file with 2 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down

0 comments on commit e063f2d

Please sign in to comment.