Skip to content
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
11 changes: 10 additions & 1 deletion octomap/src/Pointcloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,9 @@

#if defined(_MSC_VER) || defined(_LIBCPP_VERSION)
#include <algorithm>
#if __cplusplus > 199711L
#include <random>
#endif
#else
#include <ext/algorithm>
#endif
Expand Down Expand Up @@ -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<point3d_collection>(samples), num_samples);
Expand Down