test_multivariate_uniform_distribution.cpp
Go to the documentation of this file.
1 // Copyright 2024 Ekumen, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <gmock/gmock.h>
16 #include <gtest/gtest.h>
17 
18 #include <cstddef>
19 #include <unordered_map>
20 
21 #include <range/v3/range/primitives.hpp>
22 #include <range/v3/view/take_exactly.hpp>
23 
27 #include "beluga/views/sample.hpp"
28 
29 namespace {
30 
33 
34 TEST(MultivariateUniformDistribution, BoundingRegion2d) {
35  constexpr double kTolerance = 0.01;
36  auto region = Eigen::AlignedBox2d{};
37  region.min() = Eigen::Vector2d{3.00, -2.00};
38  region.max() = region.min() + kTolerance * Eigen::Vector2d::Ones();
39  auto distribution = beluga::MultivariateUniformDistribution{region};
40  auto engine = std::mt19937{std::random_device()()};
41  auto pose = distribution(engine);
42  ASSERT_THAT(pose.translation(), Vector2Near(region.min(), kTolerance));
43 }
44 
45 TEST(MultivariateUniformDistribution, BoundingRegion3d) {
46  constexpr double kTolerance = 0.01;
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();
50  auto distribution = beluga::MultivariateUniformDistribution{region};
51  auto engine = std::mt19937{std::random_device()()};
52  auto pose = distribution(engine);
53  ASSERT_THAT(pose.translation(), Vector3Near(region.min(), kTolerance));
54 }
55 
56 TEST(MultivariateUniformDistribution, GridSingleSlot) {
57  constexpr double kTolerance = 0.001;
58  constexpr double kResolution = 0.5;
59  const auto origin = Sophus::SE2d{Sophus::SO2d{}, Sophus::Vector2d{1.0, 2.0}};
60  const auto grid = beluga::testing::StaticOccupancyGrid<1, 1>{{false}, kResolution, origin};
61  auto distribution = beluga::MultivariateUniformDistribution{grid};
62  auto engine = std::mt19937{std::random_device()()};
63  auto pose = distribution(engine);
64  ASSERT_THAT(pose.translation(), Vector2Near({1.25, 2.25}, kTolerance));
65 }
66 
67 TEST(MultivariateUniformDistribution, GridSingleFreeSlot) {
68  constexpr double kTolerance = 0.001;
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},
76  kResolution,
77  };
78  auto distribution = beluga::MultivariateUniformDistribution{grid};
79  auto engine = std::mt19937{std::random_device()()};
80  auto pose = distribution(engine);
81  ASSERT_THAT(pose.translation(), Vector2Near({2.5, 2.5}, kTolerance));
82 }
83 
84 TEST(MultivariateUniformDistribution, GridSomeFreeSlots) {
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, //
90  true, false, true},
91  kResolution,
92  };
93  auto distribution = beluga::MultivariateUniformDistribution{grid};
94 
95  auto engine = std::mt19937{std::random_device()()};
96  auto output = beluga::views::sample(distribution, engine) | ranges::views::take_exactly(kSize);
97 
98  struct bucket_hash {
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);
103  }
104  };
105 
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();
110  }
111  };
112 
113  std::unordered_map<Sophus::Vector2d, std::size_t, bucket_hash, bucket_equal> buckets;
114  for (auto pose : output) {
115  ++buckets[pose.translation()];
116  }
117 
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);
124 }
125 
126 } // namespace
Sophus::SO2
kTolerance
double kTolerance
Definition: test_cluster_based_estimation.cpp:47
beluga::MultivariateUniformDistribution
MultivariateUniformDistribution(const Eigen::AlignedBox2d &) -> MultivariateUniformDistribution< Sophus::SE2d, Eigen::AlignedBox2d >
Deduction guide for bounding regions in SE2 space.
static_occupancy_grid.hpp
beluga::testing::Vector3Near
auto Vector3Near(const Sophus::Vector3< Scalar > &t, Scalar e)
Vector3 element matcher.
Definition: sophus_matchers.hpp:58
beluga::testing::Vector2Near
auto Vector2Near(const Sophus::Vector2< Scalar > &t, Scalar e)
Vector2 element matcher.
Definition: sophus_matchers.hpp:45
Sophus::SE2
Sophus::Vector2d
Vector2< double > Vector2d
beluga::testing::StaticOccupancyGrid
Definition: static_occupancy_grid.hpp:28
sophus_matchers.hpp
Implements GTest matchers for Sophus/Eigen types.
multivariate_uniform_distribution.hpp
Implementation of a multivariate uniform distribution for SE(2) and SE(3) spaces.
sample.hpp
Implementation of a sample (with replacement) range adaptor object.
beluga::MultivariateUniformDistribution
Primary template for a multivariate uniform distribution.
Definition: multivariate_uniform_distribution.hpp:40
beluga::TEST
TEST(Bresenham, MultiPassGuarantee)
Definition: test_bresenham.cpp:27


beluga
Author(s):
autogenerated on Tue Jul 16 2024 02:59:53