Skip to content

Commit

Permalink
global seed and global singleton for random numbers
Browse files Browse the repository at this point in the history
  • Loading branch information
yxlao committed Jun 24, 2022
1 parent eae520d commit 0cbd4b4
Show file tree
Hide file tree
Showing 32 changed files with 486 additions and 230 deletions.
1 change: 0 additions & 1 deletion cpp/benchmarks/core/BinaryEW.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,6 @@

#include <benchmark/benchmark.h>

#include <random>
#include <type_traits>

#include "benchmarks/benchmark_utilities/Rand.h"
Expand Down
1 change: 1 addition & 0 deletions cpp/open3d/Open3D.h.in
Original file line number Diff line number Diff line change
Expand Up @@ -113,6 +113,7 @@
#include "open3d/utility/Parallel.h"
#include "open3d/utility/ProgressBar.h"
#include "open3d/utility/ProgressReporters.h"
#include "open3d/utility/Random.h"
#include "open3d/utility/Timer.h"
#include "open3d/visualization/gui/Application.h"
#include "open3d/visualization/gui/Button.h"
Expand Down
5 changes: 2 additions & 3 deletions cpp/open3d/core/hashmap/CUDA/SlabNodeManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,12 +43,12 @@
#include <thrust/device_vector.h>

#include <memory>
#include <random>

#include "open3d/core/CUDAUtils.h"
#include "open3d/core/MemoryManager.h"
#include "open3d/core/hashmap/CUDA/SlabMacros.h"
#include "open3d/core/hashmap/HashBackendBuffer.h"
#include "open3d/utility/Random.h"

namespace open3d {
namespace core {
Expand Down Expand Up @@ -239,8 +239,7 @@ class SlabNodeManager {
public:
SlabNodeManager(const Device& device) : device_(device) {
/// Random coefficients for allocator's hash function.
std::mt19937 rng(time(0));
impl_.hash_coef_ = rng();
impl_.hash_coef_ = utility::random::RandUint32();

/// In the light version, we put num_super_blocks super blocks within
/// a single array.
Expand Down
1 change: 0 additions & 1 deletion cpp/open3d/geometry/MeshBase.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,6 @@
#include <Eigen/Dense>
#include <numeric>
#include <queue>
#include <random>
#include <tuple>

#include "open3d/geometry/BoundingVolume.h"
Expand Down
10 changes: 6 additions & 4 deletions cpp/open3d/geometry/PointCloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,6 @@
#include <Eigen/Dense>
#include <algorithm>
#include <numeric>
#include <random>

#include "open3d/geometry/BoundingVolume.h"
#include "open3d/geometry/KDTreeFlann.h"
Expand All @@ -39,6 +38,7 @@
#include "open3d/utility/Logging.h"
#include "open3d/utility/Parallel.h"
#include "open3d/utility/ProgressBar.h"
#include "open3d/utility/Random.h"

namespace open3d {
namespace geometry {
Expand Down Expand Up @@ -471,9 +471,11 @@ std::shared_ptr<PointCloud> PointCloud::RandomDownSample(
}
std::vector<size_t> indices(points_.size());
std::iota(std::begin(indices), std::end(indices), (size_t)0);
std::random_device rd;
std::mt19937 prng(rd());
std::shuffle(indices.begin(), indices.end(), prng);
{
std::lock_guard<std::mutex> lock(*utility::random::GetMutex());
std::shuffle(indices.begin(), indices.end(),
*utility::random::GetEngine());
}
indices.resize((int)(sampling_ratio * points_.size()));
return SelectByIndex(indices);
}
Expand Down
6 changes: 1 addition & 5 deletions cpp/open3d/geometry/PointCloud.h
Original file line number Diff line number Diff line change
Expand Up @@ -355,17 +355,13 @@ class PointCloud : public Geometry3D {
/// each iteration.
/// \param num_iterations Maximum number of iterations.
/// \param probability Expected probability of finding the optimal plane.
/// \param seed Sets the seed value used in the random
/// generator, set to nullopt to use a random seed value with each function
/// call.
/// \return Returns the plane model ax + by + cz + d = 0 and the indices of
/// the plane inliers.
std::tuple<Eigen::Vector4d, std::vector<size_t>> SegmentPlane(
const double distance_threshold = 0.01,
const int ransac_n = 3,
const int num_iterations = 100,
const double probability = 0.99999999,
utility::optional<int> seed = utility::nullopt) const;
const double probability = 0.99999999) const;

/// \brief Factory function to create a pointcloud from a depth image and a
/// camera model.
Expand Down
45 changes: 15 additions & 30 deletions cpp/open3d/geometry/PointCloudSegmentation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,60 +28,46 @@
#include <algorithm>
#include <iostream>
#include <iterator>
#include <mutex>
#include <numeric>
#include <random>
#include <unordered_set>

#include "open3d/geometry/PointCloud.h"
#include "open3d/geometry/TriangleMesh.h"
#include "open3d/utility/Logging.h"
#include "open3d/utility/Random.h"

namespace {
namespace open3d {
namespace geometry {

/// \class RandomSampler
///
/// \brief Helper class for random sampling
template <typename T>
class RandomSampler {
public:
explicit RandomSampler(const size_t size,
open3d::utility::optional<int> seed)
: size_(size) {
if (!seed.has_value()) {
std::random_device rd;
seed = rd();
}
rng_ = std::mt19937(seed.value());
}
explicit RandomSampler(const size_t total_size) : total_size_(total_size) {}

std::vector<T> operator()(size_t sample_size) {
std::lock_guard<std::mutex> guard(mutex_);

std::vector<T> sample;
sample.reserve(sample_size);
std::vector<T> samples;
samples.reserve(sample_size);

size_t valid_sample = 0;
while (valid_sample < sample_size) {
const size_t idx = rng_() % size_;
if (std::find(sample.begin(), sample.end(), idx) == sample.end()) {
sample.push_back(idx);
const size_t idx = utility::random::RandUint32() % total_size_;
// Well, this is slow. But typically the sample_size is small.
if (std::find(samples.begin(), samples.end(), idx) ==
samples.end()) {
samples.push_back(idx);
valid_sample++;
}
}

return sample;
return samples;
}

private:
size_t size_;
std::mt19937 rng_;
std::mutex mutex_;
size_t total_size_;
};
} // namespace

namespace open3d {
namespace geometry {

/// \class RANSACResult
///
Expand Down Expand Up @@ -181,8 +167,7 @@ std::tuple<Eigen::Vector4d, std::vector<size_t>> PointCloud::SegmentPlane(
const double distance_threshold /* = 0.01 */,
const int ransac_n /* = 3 */,
const int num_iterations /* = 100 */,
const double probability /* = 0.99999999 */,
utility::optional<int> seed /* = utility::nullopt */) const {
const double probability /* = 0.99999999 */) const {
if (probability <= 0 || probability > 1) {
utility::LogError("Probability must be > 0 or <= 1.0");
}
Expand All @@ -193,7 +178,7 @@ std::tuple<Eigen::Vector4d, std::vector<size_t>> PointCloud::SegmentPlane(
Eigen::Vector4d best_plane_model = Eigen::Vector4d(0, 0, 0, 0);

size_t num_points = points_.size();
RandomSampler<size_t> sampler(num_points, seed);
RandomSampler<size_t> sampler(num_points);

// Return if ransac_n is less than the required plane model parameters.
if (ransac_n < 3) {
Expand Down
27 changes: 9 additions & 18 deletions cpp/open3d/geometry/TriangleMesh.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,6 @@
#include <Eigen/Dense>
#include <numeric>
#include <queue>
#include <random>
#include <tuple>

#include "open3d/geometry/BoundingVolume.h"
Expand All @@ -39,6 +38,7 @@
#include "open3d/geometry/Qhull.h"
#include "open3d/utility/Logging.h"
#include "open3d/utility/Parallel.h"
#include "open3d/utility/Random.h"

namespace open3d {
namespace geometry {
Expand Down Expand Up @@ -454,8 +454,7 @@ std::shared_ptr<PointCloud> TriangleMesh::SamplePointsUniformlyImpl(
size_t number_of_points,
std::vector<double> &triangle_areas,
double surface_area,
bool use_triangle_normal,
int seed) {
bool use_triangle_normal) {
if (surface_area <= 0) {
utility::LogError("Invalid surface area {}, it must be > 0.",
surface_area);
Expand All @@ -471,12 +470,7 @@ std::shared_ptr<PointCloud> TriangleMesh::SamplePointsUniformlyImpl(
// sample point cloud
bool has_vert_normal = HasVertexNormals();
bool has_vert_color = HasVertexColors();
if (seed == -1) {
std::random_device rd;
seed = rd();
}
std::mt19937 mt(seed);
std::uniform_real_distribution<double> dist(0.0, 1.0);
utility::random::UniformDoubleGenerator uniform_generator(0.0, 1.0);
auto pcd = std::make_shared<PointCloud>();
pcd->points_.resize(number_of_points);
if (has_vert_normal || use_triangle_normal) {
Expand All @@ -492,8 +486,8 @@ std::shared_ptr<PointCloud> TriangleMesh::SamplePointsUniformlyImpl(
for (size_t tidx = 0; tidx < triangles_.size(); ++tidx) {
size_t n = size_t(std::round(triangle_areas[tidx] * number_of_points));
while (point_idx < n) {
double r1 = dist(mt);
double r2 = dist(mt);
double r1 = uniform_generator();
double r2 = uniform_generator();
double a = (1 - std::sqrt(r1));
double b = std::sqrt(r1) * (1 - r2);
double c = std::sqrt(r1) * r2;
Expand Down Expand Up @@ -524,9 +518,7 @@ std::shared_ptr<PointCloud> TriangleMesh::SamplePointsUniformlyImpl(
}

std::shared_ptr<PointCloud> TriangleMesh::SamplePointsUniformly(
size_t number_of_points,
bool use_triangle_normal /* = false */,
int seed /* = -1 */) {
size_t number_of_points, bool use_triangle_normal /* = false */) {
if (number_of_points <= 0) {
utility::LogError("number_of_points <= 0");
}
Expand All @@ -539,15 +531,14 @@ std::shared_ptr<PointCloud> TriangleMesh::SamplePointsUniformly(
double surface_area = GetSurfaceArea(triangle_areas);

return SamplePointsUniformlyImpl(number_of_points, triangle_areas,
surface_area, use_triangle_normal, seed);
surface_area, use_triangle_normal);
}

std::shared_ptr<PointCloud> TriangleMesh::SamplePointsPoissonDisk(
size_t number_of_points,
double init_factor /* = 5 */,
const std::shared_ptr<PointCloud> pcl_init /* = nullptr */,
bool use_triangle_normal /* = false */,
int seed /* = -1 */) {
bool use_triangle_normal /* = false */) {
if (number_of_points <= 0) {
utility::LogError("number_of_points <= 0");
}
Expand All @@ -574,7 +565,7 @@ std::shared_ptr<PointCloud> TriangleMesh::SamplePointsPoissonDisk(
if (pcl_init == nullptr) {
pcl = SamplePointsUniformlyImpl(size_t(init_factor * number_of_points),
triangle_areas, surface_area,
use_triangle_normal, seed);
use_triangle_normal);
} else {
pcl = std::make_shared<PointCloud>();
pcl->points_ = pcl_init->points_;
Expand Down
14 changes: 3 additions & 11 deletions cpp/open3d/geometry/TriangleMesh.h
Original file line number Diff line number Diff line change
Expand Up @@ -358,21 +358,16 @@ class TriangleMesh : public MeshBase {
size_t number_of_points,
std::vector<double> &triangle_areas,
double surface_area,
bool use_triangle_normal,
int seed);
bool use_triangle_normal);

/// Function to sample points uniformly from the mesh.
///
/// \param number_of_points points uniformly from the mesh.
/// \param use_triangle_normal Set to true to assign the triangle normals to
/// the returned points instead of the interpolated vertex normals. The
/// triangle normals will be computed and added to the mesh if necessary.
/// \param seed Sets the seed value used in the random generator, set to -1
/// to use a random seed value with each function call.
std::shared_ptr<PointCloud> SamplePointsUniformly(
size_t number_of_points,
bool use_triangle_normal = false,
int seed = -1);
size_t number_of_points, bool use_triangle_normal = false);

/// Function to sample points from the mesh with Possion disk, based on the
/// method presented in Yuksel, "Sample Elimination for Generating Poisson
Expand All @@ -386,14 +381,11 @@ class TriangleMesh : public MeshBase {
/// \param use_triangle_normal If True assigns the triangle normals instead
/// of the interpolated vertex normals to the returned points. The triangle
/// normals will be computed and added to the mesh if necessary.
/// \param seed Sets the seed value used in the random generator, set to -1
/// to use a random seed value with each function call.
std::shared_ptr<PointCloud> SamplePointsPoissonDisk(
size_t number_of_points,
double init_factor = 5,
const std::shared_ptr<PointCloud> pcl_init = nullptr,
bool use_triangle_normal = false,
int seed = -1);
bool use_triangle_normal = false);

/// Function to subdivide triangle mesh using the simple midpoint algorithm.
/// Each triangle is subdivided into four triangles per iteration and the
Expand Down
6 changes: 2 additions & 4 deletions cpp/open3d/pipelines/registration/FastGlobalRegistration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,8 @@
#include "open3d/geometry/PointCloud.h"
#include "open3d/pipelines/registration/Feature.h"
#include "open3d/pipelines/registration/Registration.h"
#include "open3d/utility/Helper.h"
#include "open3d/utility/Logging.h"
#include "open3d/utility/Random.h"

namespace open3d {
namespace pipelines {
Expand Down Expand Up @@ -88,9 +88,7 @@ static std::vector<std::pair<int, int>> AdvancedMatching(
int ncorr = static_cast<int>(corres_cross.size());
int number_of_trial = ncorr * 100;

unsigned int seed_val = option.seed_.has_value() ? option.seed_.value()
: std::random_device{}();
utility::UniformRandIntGenerator rand_generator(0, ncorr - 1, seed_val);
utility::random::UniformIntGenerator rand_generator(0, ncorr - 1);
std::vector<std::pair<int, int>> corres_tuple;
for (i = 0; i < number_of_trial; i++) {
rand0 = rand_generator();
Expand Down
24 changes: 9 additions & 15 deletions cpp/open3d/pipelines/registration/FastGlobalRegistration.h
Original file line number Diff line number Diff line change
Expand Up @@ -66,26 +66,22 @@ class FastGlobalRegistrationOption {
/// \param maximum_tuple_count Maximum numer of tuples.
/// \param tuple_test Set to `true` to perform geometric compatibility tests
/// on initial set of correspondences.
/// \param seed Random seed.
FastGlobalRegistrationOption(
double division_factor = 1.4,
bool use_absolute_scale = false,
bool decrease_mu = true,
double maximum_correspondence_distance = 0.025,
int iteration_number = 64,
double tuple_scale = 0.95,
int maximum_tuple_count = 1000,
bool tuple_test = true,
utility::optional<unsigned int> seed = utility::nullopt)
FastGlobalRegistrationOption(double division_factor = 1.4,
bool use_absolute_scale = false,
bool decrease_mu = true,
double maximum_correspondence_distance = 0.025,
int iteration_number = 64,
double tuple_scale = 0.95,
int maximum_tuple_count = 1000,
bool tuple_test = true)
: division_factor_(division_factor),
use_absolute_scale_(use_absolute_scale),
decrease_mu_(decrease_mu),
maximum_correspondence_distance_(maximum_correspondence_distance),
iteration_number_(iteration_number),
tuple_scale_(tuple_scale),
maximum_tuple_count_(maximum_tuple_count),
tuple_test_(tuple_test),
seed_(seed) {}
tuple_test_(tuple_test) {}
~FastGlobalRegistrationOption() {}

public:
Expand All @@ -109,8 +105,6 @@ class FastGlobalRegistrationOption {
/// Set to `true` to perform geometric compatibility tests on initial set of
/// correspondences.
bool tuple_test_;
/// Random seed
utility::optional<unsigned int> seed_;
};

/// \brief Fast Global Registration based on a given set of correspondences.
Expand Down
Loading

0 comments on commit 0cbd4b4

Please sign in to comment.