Skip to content

Commit

Permalink
Added load_pcd_recursive and use it in regression_test
Browse files Browse the repository at this point in the history
Signed-off-by: Shintaro Sakoda <[email protected]>
  • Loading branch information
SakodaShintaro committed Sep 10, 2024
1 parent 6a705b5 commit 494452f
Show file tree
Hide file tree
Showing 2 changed files with 39 additions and 1 deletion.
2 changes: 1 addition & 1 deletion apps/regression_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ int main(int argc, char ** argv)

// load target pcd
const std::string target_pcd = input_dir + "/pointcloud_map.pcd";
const pcl::PointCloud<pcl::PointXYZ>::Ptr target_cloud = load_pcd(target_pcd);
const pcl::PointCloud<pcl::PointXYZ>::Ptr target_cloud = load_pcd_recursive(target_pcd);

// prepare sensor_pcd
const std::string source_pcd_dir = input_dir + "/sensor_pcd/";
Expand Down
38 changes: 38 additions & 0 deletions apps/util.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
#include <pcl/point_types.h>

#include <algorithm>
#include <filesystem>
#include <string>
#include <vector>

Expand All @@ -47,6 +48,43 @@ inline pcl::PointCloud<pcl::PointXYZ>::Ptr load_pcd(const std::string & path)
return pcd;
}

inline pcl::PointCloud<pcl::PointXYZ>::Ptr load_pcd_recursive(const std::string & file_path)
{
pcl::PointCloud<pcl::PointXYZ>::Ptr pcd(new pcl::PointCloud<pcl::PointXYZ>());
if (!std::filesystem::exists(file_path)) {
std::cerr << "No such path: " << file_path << std::endl;
std::exit(1);
}
if (!std::filesystem::is_directory(file_path)) {
return load_pcd(file_path);
}

int pcd_count = 0;
for (const auto & file : std::filesystem::recursive_directory_iterator(file_path)) {
const std::string filename = file.path().c_str();
const std::string extension = file.path().extension().string();
if (extension != ".pcd" && extension != ".PCD") {
std::cerr << "ignore files: " << extension.c_str() << std::endl;
continue;
}
if (file.is_directory()) {
std::cerr << "ignore directory: " << filename.c_str() << std::endl;
continue;
}

// check load pcd
auto partial_pcd = load_pcd(filename);

// concatenate pcd
*pcd += *partial_pcd;

pcd_count++;
std::cout << "PCD loaded:" << filename << " (" << pcd_count << " files processed)" << std::endl;
}

return pcd;
}

inline std::vector<Eigen::Matrix4f> load_pose_list(const std::string & path)
{
/*
Expand Down

0 comments on commit 494452f

Please sign in to comment.