15 #include <gmock/gmock.h>
16 #include <gtest/gtest.h>
19 #include <unordered_map>
21 #include <range/v3/range/primitives.hpp>
22 #include <range/v3/view/take_exactly.hpp>
36 auto region = Eigen::AlignedBox2d{};
37 region.min() = Eigen::Vector2d{3.00, -2.00};
38 region.max() = region.min() +
kTolerance * Eigen::Vector2d::Ones();
40 auto engine = std::mt19937{std::random_device()()};
41 auto pose = distribution(engine);
47 auto region = Eigen::AlignedBox3d{};
48 region.min() = Eigen::Vector3d{3.00, -2.00, 1.00};
49 region.max() = region.min() +
kTolerance * Eigen::Vector3d::Ones();
51 auto engine = std::mt19937{std::random_device()()};
52 auto pose = distribution(engine);
58 constexpr
double kResolution = 0.5;
62 auto engine = std::mt19937{std::random_device()()};
63 auto pose = distribution(engine);
69 constexpr
double kResolution = 1.0;
71 {
true,
true,
true,
true,
true,
72 true,
true,
true,
true,
true,
73 true,
true,
false,
true,
true,
74 true,
true,
true,
true,
true,
75 true,
true,
true,
true,
true},
79 auto engine = std::mt19937{std::random_device()()};
80 auto pose = distribution(engine);
85 constexpr std::size_t kSize = 100
'000;
86 constexpr double kResolution = 1.0;
87 const auto grid = beluga::testing::StaticOccupancyGrid<3, 3>{
88 {true, false, true, //
89 false, true, false, //
93 auto distribution = beluga::MultivariateUniformDistribution{grid};
95 auto engine = std::mt19937{std::random_device()()};
96 auto output = beluga::views::sample(distribution, engine) | ranges::views::take_exactly(kSize);
99 std::size_t operator()(const Sophus::Vector2d& s) const noexcept {
100 const std::size_t h1 = std::hash<double>{}(s.x());
101 const std::size_t h2 = std::hash<double>{}(s.y());
102 return h1 ^ (h2 << 1);
106 struct bucket_equal {
107 bool operator()(const Sophus::Vector2d& lhs, const Sophus::Vector2d& rhs) const noexcept {
108 // good enough, since copies of the same candidate are expected to be identical copies
109 return lhs.x() == rhs.x() && lhs.y() == rhs.y();
113 std::unordered_map<Sophus::Vector2d, std::size_t, bucket_hash, bucket_equal> buckets;
114 for (auto pose : output) {
115 ++buckets[pose.translation()];
118 constexpr double kTolerance = 0.01;
119 ASSERT_EQ(ranges::size(buckets), 4);
120 ASSERT_NEAR(static_cast<double>(buckets[Sophus::Vector2d(1.5, 0.5)]) / kSize, 0.25, kTolerance);
121 ASSERT_NEAR(static_cast<double>(buckets[Sophus::Vector2d(0.5, 1.5)]) / kSize, 0.25, kTolerance);
122 ASSERT_NEAR(static_cast<double>(buckets[Sophus::Vector2d(2.5, 1.5)]) / kSize, 0.25, kTolerance);
123 ASSERT_NEAR(static_cast<double>(buckets[Sophus::Vector2d(1.5, 2.5)]) / kSize, 0.25, kTolerance);