fixed segmentation fault causing by std::filesystem on some devices
This commit is contained in:
parent
d9853abdd7
commit
a349d0ca13
@ -6,8 +6,7 @@
|
|||||||
// std
|
// std
|
||||||
#include <omp.h>
|
#include <omp.h>
|
||||||
#include <time.h>
|
#include <time.h>
|
||||||
|
#include <boost/filesystem.hpp>
|
||||||
#include <filesystem>
|
|
||||||
#include <memory>
|
#include <memory>
|
||||||
#include <regex>
|
#include <regex>
|
||||||
|
|
||||||
|
|||||||
@ -6,11 +6,9 @@
|
|||||||
#include <ros/ros.h>
|
#include <ros/ros.h>
|
||||||
#include <sensor_msgs/CameraInfo.h>
|
#include <sensor_msgs/CameraInfo.h>
|
||||||
#include <yaml-cpp/yaml.h>
|
#include <yaml-cpp/yaml.h>
|
||||||
|
#include <boost/filesystem.hpp>
|
||||||
#include <cmath>
|
#include <cmath>
|
||||||
#include <filesystem>
|
|
||||||
#include <memory>
|
#include <memory>
|
||||||
|
|
||||||
#include "std_msgs/Empty.h"
|
#include "std_msgs/Empty.h"
|
||||||
// flightlib
|
// flightlib
|
||||||
#include "flightlib/bridges/unity_bridge.hpp"
|
#include "flightlib/bridges/unity_bridge.hpp"
|
||||||
|
|||||||
@ -318,15 +318,15 @@ bool VecEnv<EnvBase>::spawnTreesAndSavePointcloud(int ply_id_in, float spacing)
|
|||||||
template<typename EnvBase>
|
template<typename EnvBase>
|
||||||
void VecEnv<EnvBase>::generateMaps() {
|
void VecEnv<EnvBase>::generateMaps() {
|
||||||
std::vector<std::string> ply_files;
|
std::vector<std::string> ply_files;
|
||||||
for (const auto& entry : std::filesystem::directory_iterator(ply_path_)) {
|
for (const auto& entry : boost::filesystem::directory_iterator(ply_path_)) {
|
||||||
if (entry.is_regular_file() && entry.path().extension() == ".ply") {
|
if (boost::filesystem::is_regular_file(entry) && entry.path().extension() == ".ply") {
|
||||||
ply_files.push_back(entry.path().string());
|
ply_files.push_back(entry.path().string());
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Sort according to the number of the filename.
|
// 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) {
|
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) {
|
for (auto ply_file : ply_files) {
|
||||||
|
|||||||
@ -202,8 +202,8 @@ bool FlightPilot::loadParams(const YAML::Node& cfg) {
|
|||||||
}
|
}
|
||||||
pointcloud_resolution_ = cfg["unity"]["pointcloud_resolution"].as<Scalar>();
|
pointcloud_resolution_ = cfg["unity"]["pointcloud_resolution"].as<Scalar>();
|
||||||
ply_path_ = getenv("FLIGHTMARE_PATH") + cfg["ply_path"].as<std::string>();
|
ply_path_ = getenv("FLIGHTMARE_PATH") + cfg["ply_path"].as<std::string>();
|
||||||
if (!std::filesystem::exists(ply_path_)) {
|
if (!boost::filesystem::exists(ply_path_)) {
|
||||||
std::filesystem::create_directories(ply_path_);
|
boost::filesystem::create_directories(ply_path_);
|
||||||
std::cout << "Directory created: " << ply_path_ << std::endl;
|
std::cout << "Directory created: " << ply_path_ << std::endl;
|
||||||
}
|
}
|
||||||
return true;
|
return true;
|
||||||
|
|||||||
Loading…
x
Reference in New Issue
Block a user