Skip to content

Commit

Permalink
Enable C++17 filesystem in the future (PointCloudLibrary#5921)
Browse files Browse the repository at this point in the history
* Enable C++17 filesystem

* Fix format complaint

* Fix ubuntu build error

* Fix apps build error

* Fix format complaint

* Switch Ubuntu 23.04 to C++17

* Revert doc/tutorials and outofcore

* Revert examples/outofcore

* Revert test/outofcore

* Revert recognition

* Fix apps/face_detection build error

* Address review

* Address more review
  • Loading branch information
cybaol authored Jan 17, 2024
1 parent eb6bdd7 commit c295be9
Show file tree
Hide file tree
Showing 54 changed files with 523 additions and 223 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ class MeshSource : public Source<PointInT> {
loadOrGenerate(std::string& dir, std::string& model_path, ModelT& model)
{
const std::string pathmodel = dir + '/' + model.class_ + '/' + model.id_;
bf::path trained_dir = pathmodel;
pcl_fs::path trained_dir = pathmodel;

model.views_.reset(new std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr>);
model.poses_.reset(
Expand All @@ -90,12 +90,12 @@ class MeshSource : public Source<PointInT> {
model.assembled_.reset(new pcl::PointCloud<pcl::PointXYZ>);
uniform_sampling(model_path, 100000, *model.assembled_, model_scale_);

if (bf::exists(trained_dir)) {
if (pcl_fs::exists(trained_dir)) {
// load views, poses and self-occlusions
std::vector<std::string> view_filenames;
for (const auto& dir_entry : bf::directory_iterator(trained_dir)) {
for (const auto& dir_entry : pcl_fs::directory_iterator(trained_dir)) {
// check if its a directory, then get models in it
if (!(bf::is_directory(dir_entry))) {
if (!(pcl_fs::is_directory(dir_entry))) {
// check that it is a ply file and then add, otherwise ignore..
std::vector<std::string> strs;
std::vector<std::string> strs_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ pcl::rec_3d_framework::GlobalNNPipeline<Distance, PointInT, FeatureT>::
std::string path =
source_->getModelDescriptorDir(models->at(i), training_dir_, descr_name_);

for (const auto& dir_entry : bf::directory_iterator(path)) {
for (const auto& dir_entry : pcl_fs::directory_iterator(path)) {
std::string file_name = (dir_entry.path().filename()).string();

std::vector<std::string> strs;
Expand Down Expand Up @@ -177,9 +177,9 @@ pcl::rec_3d_framework::GlobalNNPipeline<Distance, PointInT, FeatureT>::initializ
std::string path =
source_->getModelDescriptorDir(models->at(i), training_dir_, descr_name_);

bf::path desc_dir = path;
if (!bf::exists(desc_dir))
bf::create_directory(desc_dir);
pcl_fs::path desc_dir = path;
if (!pcl_fs::exists(desc_dir))
pcl_fs::create_directory(desc_dir);

const std::string path_view = path + "/view_" + std::to_string(v) + ".pcd";
pcl::io::savePCDFileBinary(path_view, *processed);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ pcl::rec_3d_framework::GlobalNNCRHRecognizer<Distance, PointInT, FeatureT>::
std::string path =
source_->getModelDescriptorDir(models->at(i), training_dir_, descr_name_);

for (const auto& dir_entry : bf::directory_iterator(path)) {
for (const auto& dir_entry : pcl_fs::directory_iterator(path)) {
std::string file_name = (dir_entry.path().filename()).string();

std::vector<std::string> strs;
Expand Down Expand Up @@ -412,9 +412,9 @@ pcl::rec_3d_framework::GlobalNNCRHRecognizer<Distance, PointInT, FeatureT>::init
std::string path =
source_->getModelDescriptorDir(models->at(i), training_dir_, descr_name_);

bf::path desc_dir = path;
if (!bf::exists(desc_dir))
bf::create_directory(desc_dir);
pcl_fs::path desc_dir = path;
if (!pcl_fs::exists(desc_dir))
pcl_fs::create_directory(desc_dir);

const std::string path_view = path + "/view_" + std::to_string(v) + ".pcd";
pcl::io::savePCDFileBinary(path_view, *processed);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,8 +51,8 @@ pcl::rec_3d_framework::GlobalNNCVFHRecognizer<Distance, PointInT, FeatureT>::
const std::string dir = path + "/roll_trans_" + std::to_string(view_id) + '_' +
std::to_string(d_id) + ".txt";

const bf::path file_path = dir;
if (bf::exists(file_path)) {
const pcl_fs::path file_path = dir;
if (pcl_fs::exists(file_path)) {
PersistenceUtils::readMatrixFromFile(dir, pose_matrix);
return true;
}
Expand Down Expand Up @@ -108,7 +108,7 @@ pcl::rec_3d_framework::GlobalNNCVFHRecognizer<Distance, PointInT, FeatureT>::
std::string path =
source_->getModelDescriptorDir(models->at(i), training_dir_, descr_name_);

for (const auto& dir_entry : bf::directory_iterator(path)) {
for (const auto& dir_entry : pcl_fs::directory_iterator(path)) {
std::string file_name = (dir_entry.path().filename()).string();

std::vector<std::string> strs;
Expand Down Expand Up @@ -608,9 +608,9 @@ pcl::rec_3d_framework::GlobalNNCVFHRecognizer<Distance, PointInT, FeatureT>::ini
std::string path =
source_->getModelDescriptorDir(models->at(i), training_dir_, descr_name_);

bf::path desc_dir = path;
if (!bf::exists(desc_dir))
bf::create_directory(desc_dir);
pcl_fs::path desc_dir = path;
if (!pcl_fs::exists(desc_dir))
pcl_fs::create_directory(desc_dir);

const std::string path_view = path + "/view_" + std::to_string(v) + ".pcd";
pcl::io::savePCDFileBinary(path_view, *processed);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ pcl::rec_3d_framework::LocalRecognitionPipeline<Distance, PointInT, FeatureT>::
std::string path =
source_->getModelDescriptorDir(models->at(i), training_dir_, descr_name_);

for (const auto& dir_entry : bf::directory_iterator(path)) {
for (const auto& dir_entry : pcl_fs::directory_iterator(path)) {
std::string file_name = (dir_entry.path().filename()).string();

std::vector<std::string> strs;
Expand Down Expand Up @@ -150,9 +150,9 @@ pcl::rec_3d_framework::LocalRecognitionPipeline<Distance, PointInT, FeatureT>::
std::string path =
source_->getModelDescriptorDir(models->at(i), training_dir_, descr_name_);

bf::path desc_dir = path;
if (!bf::exists(desc_dir))
bf::create_directory(desc_dir);
pcl_fs::path desc_dir = path;
if (!pcl_fs::exists(desc_dir))
pcl_fs::create_directory(desc_dir);

const std::string path_view = path = "/view_" + std::to_string(v) + ".pcd";
pcl::io::savePCDFileBinary(path_view, *processed);
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,14 @@
#include <pcl/io/pcd_io.h>

#include <boost/algorithm/string.hpp>

#if (__cplusplus >= 201703L)
#include <filesystem>
namespace pcl_fs = std::filesystem;
#else
#include <boost/filesystem.hpp>
namespace pcl_fs = boost::filesystem;
#endif

#include <fstream>

Expand Down
24 changes: 12 additions & 12 deletions apps/3d_rec_framework/src/tools/local_recognition_mian_dataset.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,17 +22,17 @@
#include <flann/algorithms/dist.h>

void
getScenesInDirectory(bf::path& dir,
getScenesInDirectory(pcl_fs::path& dir,
std::string& rel_path_so_far,
std::vector<std::string>& relative_paths)
{
// list models in MODEL_FILES_DIR_ and return list
for (const auto& dir_entry : bf::directory_iterator(dir)) {
for (const auto& dir_entry : pcl_fs::directory_iterator(dir)) {
// check if its a directory, then get models in it
if (bf::is_directory(dir_entry)) {
if (pcl_fs::is_directory(dir_entry)) {
std::string so_far =
rel_path_so_far + (dir_entry.path().filename()).string() + "/";
bf::path curr_path = dir_entry.path();
pcl_fs::path curr_path = dir_entry.path();
getScenesInDirectory(curr_path, so_far, relative_paths);
}
else {
Expand Down Expand Up @@ -86,7 +86,7 @@ recognizeAndVisualize(
{

// read mians scenes
bf::path ply_files_dir = scenes_dir;
pcl_fs::path ply_files_dir = scenes_dir;
std::vector<std::string> files;
std::string start;
getScenesInDirectory(ply_files_dir, start, files);
Expand Down Expand Up @@ -223,18 +223,18 @@ recognizeAndVisualize(
}

void
getModelsInDirectory(bf::path& dir,
getModelsInDirectory(pcl_fs::path& dir,
std::string& rel_path_so_far,
std::vector<std::string>& relative_paths,
std::string& ext)
{
for (const auto& dir_entry : bf::directory_iterator(dir)) {
for (const auto& dir_entry : pcl_fs::directory_iterator(dir)) {
// check if its a directory, then get models in it
if (bf::is_directory(dir_entry)) {
if (pcl_fs::is_directory(dir_entry)) {
std::string so_far =
rel_path_so_far + (dir_entry.path().filename()).string() + "/";

bf::path curr_path = dir_entry.path();
pcl_fs::path curr_path = dir_entry.path();
getModelsInDirectory(curr_path, so_far, relative_paths, ext);
}
else {
Expand Down Expand Up @@ -315,16 +315,16 @@ main(int argc, char** argv)
return -1;
}

bf::path models_dir_path = path;
if (!bf::exists(models_dir_path)) {
pcl_fs::path models_dir_path = path;
if (!pcl_fs::exists(models_dir_path)) {
PCL_ERROR("Models dir path %s does not exist, use -models_dir [dir] option\n",
path.c_str());
return -1;
}
std::vector<std::string> files;
std::string start;
std::string ext = std::string("ply");
bf::path dir = models_dir_path;
pcl_fs::path dir = models_dir_path;
getModelsInDirectory(dir, start, files, ext);
assert(files.size() == 4);

Expand Down
13 changes: 10 additions & 3 deletions apps/in_hand_scanner/src/offline_integration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,14 @@
#include <pcl/io/pcd_io.h>

#include <boost/algorithm/string/case_conv.hpp>

#if (__cplusplus >= 201703L)
#include <filesystem>
namespace pcl_fs = std::filesystem;
#else
#include <boost/filesystem.hpp>
namespace pcl_fs = boost::filesystem;
#endif

#include <QApplication>
#include <QFileDialog>
Expand Down Expand Up @@ -186,14 +193,14 @@ pcl::ihs::OfflineIntegration::getFilesFromDirectory(
const std::string& extension,
std::vector<std::string>& files) const
{
if (path_dir.empty() || !boost::filesystem::exists(path_dir)) {
if (path_dir.empty() || !pcl_fs::exists(path_dir)) {
std::cerr << "ERROR in offline_integration.cpp: Invalid path\n '" << path_dir
<< "'\n";
return (false);
}

boost::filesystem::directory_iterator it_end;
for (boost::filesystem::directory_iterator it(path_dir); it != it_end; ++it) {
pcl_fs::directory_iterator it_end;
for (pcl_fs::directory_iterator it(path_dir); it != it_end; ++it) {
if (!is_directory(it->status()) &&
boost::algorithm::to_upper_copy(it->path().extension().string()) ==
boost::algorithm::to_upper_copy(extension)) {
Expand Down
16 changes: 12 additions & 4 deletions apps/include/pcl/apps/face_detection/face_detection_apps_utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,14 @@

#pragma once

#if (__cplusplus >= 201703L)
#include <filesystem>
namespace pcl_fs = std::filesystem;
#else
#include <boost/filesystem.hpp>
namespace pcl_fs = boost::filesystem;
#endif

namespace face_detection_apps_utils {

inline bool
Expand Down Expand Up @@ -65,18 +73,18 @@ sortFiles(const std::string& file1, const std::string& file2)
}

inline void
getFilesInDirectory(bf::path& dir,
getFilesInDirectory(pcl_fs::path& dir,
std::string& rel_path_so_far,
std::vector<std::string>& relative_paths,
std::string& ext)
{
for (const auto& dir_entry : bf::directory_iterator(dir)) {
for (const auto& dir_entry : pcl_fs::directory_iterator(dir)) {
// check if its a directory, then get models in it
if (bf::is_directory(dir_entry)) {
if (pcl_fs::is_directory(dir_entry)) {
std::string so_far =
rel_path_so_far + (dir_entry.path().filename()).string() + "/";

bf::path curr_path = dir_entry.path();
pcl_fs::path curr_path = dir_entry.path();
getFilesInDirectory(curr_path, so_far, relative_paths, ext);
}
else {
Expand Down
8 changes: 7 additions & 1 deletion apps/include/pcl/apps/pcd_video_player.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,13 @@
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>

#if (__cplusplus >= 201703L)
#include <filesystem>
namespace pcl_fs = std::filesystem;
#else
#include <boost/filesystem.hpp>
namespace pcl_fs = boost::filesystem;
#endif

#include <QMainWindow>
#include <QMutex>
Expand Down Expand Up @@ -100,7 +106,7 @@ class PCDVideoPlayer : public QMainWindow {
QString dir_;

std::vector<std::string> pcd_files_;
std::vector<boost::filesystem::path> pcd_paths_;
std::vector<pcl_fs::path> pcd_paths_;

/** \brief The current displayed frame */
unsigned int current_frame_;
Expand Down
10 changes: 7 additions & 3 deletions apps/src/face_detection/filesystem_face_detection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,9 +13,13 @@
#include <pcl/apps/face_detection/face_detection_apps_utils.h>
// clang-format on

#if (__cplusplus >= 201703L)
#include <filesystem>
namespace pcl_fs = std::filesystem;
#else
#include <boost/filesystem.hpp>

namespace bf = boost::filesystem;
namespace pcl_fs = boost::filesystem;
#endif

bool SHOW_GT = false;
bool VIDEO = false;
Expand Down Expand Up @@ -222,7 +226,7 @@ main(int argc, char** argv)
// recognize all files in directory...
std::string start;
std::string ext = std::string("pcd");
bf::path dir = test_directory;
pcl_fs::path dir = test_directory;

std::vector<std::string> files;
face_detection_apps_utils::getFilesInDirectory(dir, start, files, ext);
Expand Down
11 changes: 8 additions & 3 deletions apps/src/openni_grab_frame.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,13 @@
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>

#if (__cplusplus >= 201703L)
#include <filesystem>
namespace pcl_fs = std::filesystem;
#else
#include <boost/filesystem.hpp>
namespace pcl_fs = boost::filesystem;
#endif

#include <mutex>

Expand Down Expand Up @@ -75,7 +81,6 @@ using namespace std::chrono_literals;
#endif

using namespace pcl::console;
using namespace boost::filesystem;

template <typename PointType>
class OpenNIGrabFrame {
Expand Down Expand Up @@ -222,7 +227,7 @@ class OpenNIGrabFrame {
bool paused,
bool visualizer)
{
boost::filesystem::path path(filename);
pcl_fs::path path(filename);

if (filename.empty()) {
dir_name_ = ".";
Expand All @@ -231,7 +236,7 @@ class OpenNIGrabFrame {
else {
dir_name_ = path.parent_path().string();

if (!dir_name_.empty() && !boost::filesystem::exists(path.parent_path())) {
if (!dir_name_.empty() && !pcl_fs::exists(path.parent_path())) {
std::cerr << "directory \"" << path.parent_path() << "\" does not exist!\n";
exit(1);
}
Expand Down
3 changes: 0 additions & 3 deletions apps/src/openni_grab_images.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,12 +44,9 @@
#include <pcl/visualization/image_viewer.h>
#include <pcl/point_types.h>

#include <boost/filesystem.hpp>

#include <mutex>

using namespace pcl::console;
using namespace boost::filesystem;

class OpenNIGrabFrame {
public:
Expand Down
3 changes: 0 additions & 3 deletions apps/src/organized_segmentation_demo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,6 @@
#include <vtkRendererCollection.h>
#include <vtkRenderWindow.h>

// #include <boost/filesystem.hpp> // for boost::filesystem::directory_iterator
#include <boost/signals2/connection.hpp> // for boost::signals2::connection

void
displayPlanarRegions(
std::vector<pcl::PlanarRegion<PointT>,
Expand Down
Loading

0 comments on commit c295be9

Please sign in to comment.