fixed segmentation fault causing by std::filesystem on some devices

This commit is contained in:
TJU_Lu 2024-12-09 10:31:13 +08:00
parent d9853abdd7
commit a349d0ca13
4 changed files with 10 additions and 13 deletions

View File

@ -6,8 +6,7 @@
// std
#include <omp.h>
#include <time.h>
#include <filesystem>
#include <boost/filesystem.hpp>
#include <memory>
#include <regex>

View File

@ -6,11 +6,9 @@
#include <ros/ros.h>
#include <sensor_msgs/CameraInfo.h>
#include <yaml-cpp/yaml.h>
#include <boost/filesystem.hpp>
#include <cmath>
#include <filesystem>
#include <memory>
#include "std_msgs/Empty.h"
// flightlib
#include "flightlib/bridges/unity_bridge.hpp"

View File

@ -318,15 +318,15 @@ bool VecEnv<EnvBase>::spawnTreesAndSavePointcloud(int ply_id_in, float spacing)
template<typename EnvBase>
void VecEnv<EnvBase>::generateMaps() {
std::vector<std::string> ply_files;
for (const auto& entry : std::filesystem::directory_iterator(ply_path_)) {
if (entry.is_regular_file() && entry.path().extension() == ".ply") {
ply_files.push_back(entry.path().string());
}
}
for (const auto& entry : boost::filesystem::directory_iterator(ply_path_)) {
if (boost::filesystem::is_regular_file(entry) && entry.path().extension() == ".ply") {
ply_files.push_back(entry.path().string());
}
}
// Sort according to the number of the filename.
std::sort(ply_files.begin(), ply_files.end(), [this](const std::string& a, const std::string& b) {
return extract_number(std::filesystem::path(a).filename().string()) < extract_number(std::filesystem::path(b).filename().string());
return extract_number(boost::filesystem::path(a).filename().string()) < extract_number(boost::filesystem::path(b).filename().string());
});
for (auto ply_file : ply_files) {

View File

@ -202,8 +202,8 @@ bool FlightPilot::loadParams(const YAML::Node& cfg) {
}
pointcloud_resolution_ = cfg["unity"]["pointcloud_resolution"].as<Scalar>();
ply_path_ = getenv("FLIGHTMARE_PATH") + cfg["ply_path"].as<std::string>();
if (!std::filesystem::exists(ply_path_)) {
std::filesystem::create_directories(ply_path_);
if (!boost::filesystem::exists(ply_path_)) {
boost::filesystem::create_directories(ply_path_);
std::cout << "Directory created: " << ply_path_ << std::endl;
}
return true;