Skip to content

Commit

Permalink
fix(map_loader): change error handling when pcd_metadata file not fou…
Browse files Browse the repository at this point in the history
…nd (#6227)

Changed error handling when pcd_metadata file not found

Signed-off-by: Shintaro Sakoda <shintaro.sakoda@tier4.jp>
  • Loading branch information
SakodaShintaro authored Jan 30, 2024
1 parent 5e8da39 commit 25bc636
Showing 1 changed file with 3 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -90,8 +90,9 @@ std::map<std::string, PCDFileMetadata> PointCloudMapLoaderNode::getPCDMetadata(
{
std::map<std::string, PCDFileMetadata> 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);
Expand Down

0 comments on commit 25bc636

Please sign in to comment.