diff --git a/octomap/src/Pointcloud.cpp b/octomap/src/Pointcloud.cpp index 09349db0..74127399 100644 --- a/octomap/src/Pointcloud.cpp +++ b/octomap/src/Pointcloud.cpp @@ -38,6 +38,9 @@ #if defined(_MSC_VER) || defined(_LIBCPP_VERSION) #include + #if __cplusplus > 199711L + #include + #endif #else #include #endif @@ -210,7 +213,13 @@ namespace octomap { #if defined(_MSC_VER) || defined(_LIBCPP_VERSION) samples.reserve(this->size()); samples.insert(samples.end(), this->begin(), this->end()); - std::random_shuffle(samples.begin(), samples.end()); + #if __cplusplus > 199711L + std::random_device r; + std::mt19937 urbg(r()); + std::shuffle(samples.begin(), samples.end(), urbg); + #else + std::random_shuffle(samples.begin(), samples.end()); + #endif samples.resize(num_samples); #else random_sample_n(begin(), end(), std::back_insert_iterator(samples), num_samples);