Skip to content

Commit

Permalink
[common] Give RandomGenerator efficient default and move constructors (
Browse files Browse the repository at this point in the history
…RobotLocomotion#16633)

Copying 5000 bytes of storage during a move is wasteful; better to just
swap a heap pointer.

Calculating 624 random integers in the default constructor is wasteful,
if we're only trying to allocate a storage for generator that will be
moved into later (e.g., when resizing a collection of generators).

While we're here, tidy up some of its API documentation for completeness.
  • Loading branch information
jwnimmer-tri authored Feb 21, 2022
1 parent 256d7f6 commit 7e50c5d
Show file tree
Hide file tree
Showing 6 changed files with 179 additions and 25 deletions.
10 changes: 4 additions & 6 deletions bindings/pydrake/common/module_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -157,12 +157,10 @@ discussion), use e.g.
)""")
.c_str());
random_generator_cls
.def(py::init<>(),
"Default constructor. Seeds the engine with the default_seed.")
.def(py::init<RandomGenerator::result_type>(),
"Constructs the engine and initializes the state with a given "
"value.")
random_generator_cls // BR
.def(py::init<>(), doc.RandomGenerator.ctor.doc_0args)
.def(py::init<RandomGenerator::result_type>(), py::arg("seed"),
doc.RandomGenerator.ctor.doc_1args)
.def(
"__call__", [](RandomGenerator& self) { return self(); },
"Generates a pseudo-random value.");
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/common/test/module_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ def test_logging(self):
def test_random_generator(self):
g1 = mut.RandomGenerator()
self.assertEqual(g1(), 3499211612)
g2 = mut.RandomGenerator(10)
g2 = mut.RandomGenerator(seed=10)
self.assertEqual(g2(), 3312796937)

def test_random_numpy_coordination(self):
Expand Down
2 changes: 2 additions & 0 deletions common/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -476,6 +476,7 @@ drake_cc_library(
hdrs = ["random.h"],
deps = [
":autodiff",
":copyable_unique_ptr",
":essential",
":extract_double",
],
Expand Down Expand Up @@ -684,6 +685,7 @@ drake_cc_googletest(
name = "random_test",
deps = [
":random",
"//common/test_utilities:limit_malloc",
],
)

Expand Down
5 changes: 5 additions & 0 deletions common/random.cc
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,11 @@
#include "drake/common/autodiff.h"

namespace drake {
std::unique_ptr<RandomGenerator::Engine> RandomGenerator::CreateEngine(
result_type seed) {
return std::make_unique<RandomGenerator::Engine>(seed);
}

template <typename T>
T CalcProbabilityDensity(RandomDistribution distribution,
const Eigen::Ref<const VectorX<T>>& x) {
Expand Down
31 changes: 26 additions & 5 deletions common/random.h
Original file line number Diff line number Diff line change
@@ -1,9 +1,12 @@
#pragma once

#include <memory>
#include <random>

#include <Eigen/Core>

#include "drake/common/copyable_unique_ptr.h"
#include "drake/common/drake_assert.h"
#include "drake/common/drake_copyable.h"
#include "drake/common/eigen_types.h"
#include "drake/common/extract_double.h"
Expand All @@ -20,17 +23,35 @@ class RandomGenerator {

using result_type = std::mt19937::result_type;

/// Creates a generator using the `default_seed`. Actual creation of the
/// generator is deferred until first use so this constructor is fast and
/// does not allocate any heap memory.
RandomGenerator() = default;
explicit RandomGenerator(result_type value) : generator_(value) {}

static constexpr result_type min() { return std::mt19937::min(); }
static constexpr result_type max() { return std::mt19937::max(); }
result_type operator()() { return generator_(); }
/// Creates a generator using given `seed`.
explicit RandomGenerator(result_type seed)
: generator_(CreateEngine(seed)) {}

static constexpr result_type min() { return Engine::min(); }
static constexpr result_type max() { return Engine::max(); }

/// Generates a pseudo-random value.
result_type operator()() {
// Use lazy construction here, so that the default constructor can be fast.
if (generator_ == nullptr) {
generator_ = CreateEngine(default_seed);
}
return (*generator_)();
}

static constexpr result_type default_seed = std::mt19937::default_seed;

private:
std::mt19937 generator_{};
using Engine = std::mt19937;

static std::unique_ptr<Engine> CreateEngine(result_type seed);

copyable_unique_ptr<Engine> generator_;
};

/// Drake supports explicit reasoning about a few carefully chosen random
Expand Down
154 changes: 141 additions & 13 deletions common/test/random_test.cc
Original file line number Diff line number Diff line change
@@ -1,37 +1,165 @@
#include "drake/common/random.h"

#include <limits>
#include <type_traits>

#include <gtest/gtest.h>

#include "drake/common/autodiff.h"
#include "drake/common/test_utilities/limit_malloc.h"

namespace drake {
namespace {

const double kEps = std::numeric_limits<double>::epsilon();
constexpr double kEps = std::numeric_limits<double>::epsilon();

// The mt19937 inside our RandomGenerator implementation has a large block of
// pre-computed internal state that is only updated (in bulk) after a certain
// number of random outputs. Extracting this many outputs is sufficient to
// ensure that we trigger the internal update, in case it might be relevant
// to our memory-safety tests in the below.
//
// For details, refer to state_size (which is n == 624 in our case) here:
// https://en.cppreference.com/w/cpp/numeric/random/mersenne_twister_engine
constexpr int kNumSteps = 700;

GTEST_TEST(RandomGeneratorTest, Traits) {
EXPECT_TRUE(std::is_default_constructible_v<RandomGenerator>);
EXPECT_TRUE(std::is_copy_constructible_v<RandomGenerator>);
EXPECT_TRUE(std::is_copy_assignable_v<RandomGenerator>);
EXPECT_TRUE(std::is_move_constructible_v<RandomGenerator>);
EXPECT_TRUE(std::is_move_assignable_v<RandomGenerator>);
}

GTEST_TEST(RandomGeneratorTest, Efficiency) {
// Check an insanity upper bound, to demonstrate that we don't store large
// random state on the stack.
EXPECT_LE(sizeof(RandomGenerator), 64);

{
// Default construction is heap-free.
drake::test::LimitMalloc guard;
RandomGenerator dut;
}
}

// Copying a defaulted generator produces identical outputs.
GTEST_TEST(RandomGeneratorTest, Copy0) {
RandomGenerator foo;
RandomGenerator bar(foo);
for (int i = 0; i < kNumSteps; ++i) {
ASSERT_EQ(foo(), bar()) << "with i = " << i;
}
}

// Copying a seeded generator produces identical outputs.
GTEST_TEST(RandomGeneratorTest, Copy1) {
RandomGenerator foo(123);
RandomGenerator bar(foo);
for (int i = 0; i < kNumSteps; ++i) {
ASSERT_EQ(foo(), bar()) << "with i = " << i;
}
}

// Copy-assigning a defaulted generator produces identical outputs.
GTEST_TEST(RandomGeneratorTest, CopyAssign0) {
RandomGenerator foo;
RandomGenerator bar;
bar = foo;
for (int i = 0; i < kNumSteps; ++i) {
ASSERT_EQ(foo(), bar()) << "with i = " << i;
}
}

// Copy-assigning a seeded generator produces identical outputs.
GTEST_TEST(RandomGeneratorTest, CopyAssign1) {
RandomGenerator foo(123);
RandomGenerator bar;
bar = foo;
for (int i = 0; i < kNumSteps; ++i) {
ASSERT_EQ(foo(), bar()) << "with i = " << i;
}
}

// Moving from a defaulted generator produces identical outputs.
GTEST_TEST(RandomGeneratorTest, Move0) {
RandomGenerator foo;
RandomGenerator temp;
RandomGenerator bar(std::move(temp));
for (int i = 0; i < kNumSteps; ++i) {
ASSERT_EQ(foo(), bar()) << "with i = " << i;
}
}

// Moving from a seeded generator produces identical outputs.
GTEST_TEST(RandomGeneratorTest, Move1) {
RandomGenerator foo(123);
RandomGenerator temp(123);
RandomGenerator bar(std::move(temp));
for (int i = 0; i < kNumSteps; ++i) {
ASSERT_EQ(foo(), bar()) << "with i = " << i;
}
}

// Move-assigning from a defaulted generator produces identical outputs.
GTEST_TEST(RandomGeneratorTest, MoveAssign0) {
RandomGenerator foo;
RandomGenerator bar;
bar = RandomGenerator();
for (int i = 0; i < kNumSteps; ++i) {
ASSERT_EQ(foo(), bar()) << "with i = " << i;
}
}

// Move-assigning from a seeded generator produces identical outputs.
GTEST_TEST(RandomGeneratorTest, MoveAssign1) {
RandomGenerator foo(123);
RandomGenerator bar;
bar = RandomGenerator(123);
for (int i = 0; i < kNumSteps; ++i) {
ASSERT_EQ(foo(), bar()) << "with i = " << i;
}
}

// Using a moved-from defaulted generator does not segfault.
GTEST_TEST(RandomGeneratorTest, MovedFrom0) {
RandomGenerator foo;
RandomGenerator bar = std::move(foo);
for (int i = 0; i < kNumSteps; ++i) {
EXPECT_NO_THROW(foo());
EXPECT_NO_THROW(bar());
}
}

GTEST_TEST(RandomTest, CompareWith19337) {
// Using a moved-from seeded generator does not segfault.
GTEST_TEST(RandomGeneratorTest, MovedFrom1) {
RandomGenerator foo(123);
RandomGenerator bar = std::move(foo);
for (int i = 0; i < kNumSteps; ++i) {
EXPECT_NO_THROW(foo());
EXPECT_NO_THROW(bar());
}
}

GTEST_TEST(RandomGeneratorTest, CompareWith19337) {
std::mt19937 oracle;

RandomGenerator dut;
EXPECT_EQ(dut.min(), oracle.min());
EXPECT_EQ(dut.max(), oracle.max());

RandomGenerator::result_type first = dut();
auto oracle_first = oracle();
EXPECT_EQ(first, oracle_first);

for (int i = 0; i < 100; ++i) {
EXPECT_EQ(dut(), oracle());
for (int i = 0; i < kNumSteps; ++i) {
ASSERT_EQ(dut(), oracle()) << "with i = " << i;
}
}

GTEST_TEST(RandomTest, Seed) {
RandomGenerator dut1;
RandomGenerator dut2(RandomGenerator::default_seed);
for (int i = 0; i < 100; ++i) {
EXPECT_EQ(dut1(), dut2());
// The sequence from a default-constructed generator is the same as explicitly
// passing in the default seed.
GTEST_TEST(RandomGeneratorTest, DefaultMatchesSeedConstant) {
RandomGenerator foo;
RandomGenerator bar(RandomGenerator::default_seed);
for (int i = 0; i < kNumSteps; ++i) {
ASSERT_EQ(foo(), bar()) << "with i = " << i;
}
}

Expand Down

0 comments on commit 7e50c5d

Please sign in to comment.