hybrid_grid_test.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #include "cartographer/mapping/3d/hybrid_grid.h"
00018 
00019 #include <map>
00020 #include <random>
00021 #include <tuple>
00022 
00023 #include "gmock/gmock.h"
00024 
00025 namespace cartographer {
00026 namespace mapping {
00027 namespace {
00028 
00029 TEST(HybridGridTest, ApplyOdds) {
00030   HybridGrid hybrid_grid(1.f);
00031 
00032   EXPECT_FALSE(hybrid_grid.IsKnown(Eigen::Array3i(0, 0, 0)));
00033   EXPECT_FALSE(hybrid_grid.IsKnown(Eigen::Array3i(0, 1, 0)));
00034   EXPECT_FALSE(hybrid_grid.IsKnown(Eigen::Array3i(1, 0, 0)));
00035   EXPECT_FALSE(hybrid_grid.IsKnown(Eigen::Array3i(1, 1, 0)));
00036   EXPECT_FALSE(hybrid_grid.IsKnown(Eigen::Array3i(0, 0, 1)));
00037   EXPECT_FALSE(hybrid_grid.IsKnown(Eigen::Array3i(0, 1, 1)));
00038   EXPECT_FALSE(hybrid_grid.IsKnown(Eigen::Array3i(1, 0, 1)));
00039   EXPECT_FALSE(hybrid_grid.IsKnown(Eigen::Array3i(1, 1, 1)));
00040 
00041   hybrid_grid.SetProbability(Eigen::Array3i(1, 0, 1), 0.5f);
00042 
00043   hybrid_grid.ApplyLookupTable(Eigen::Array3i(1, 0, 1),
00044                                ComputeLookupTableToApplyOdds(Odds(0.9f)));
00045   hybrid_grid.FinishUpdate();
00046   EXPECT_GT(hybrid_grid.GetProbability(Eigen::Array3i(1, 0, 1)), 0.5f);
00047 
00048   hybrid_grid.SetProbability(Eigen::Array3i(0, 1, 0), 0.5f);
00049 
00050   hybrid_grid.ApplyLookupTable(Eigen::Array3i(0, 1, 0),
00051                                ComputeLookupTableToApplyOdds(Odds(0.1f)));
00052   hybrid_grid.FinishUpdate();
00053   EXPECT_LT(hybrid_grid.GetProbability(Eigen::Array3i(0, 1, 0)), 0.5f);
00054 
00055   // Tests adding odds to an unknown cell.
00056   hybrid_grid.ApplyLookupTable(Eigen::Array3i(1, 1, 1),
00057                                ComputeLookupTableToApplyOdds(Odds(0.42f)));
00058   EXPECT_NEAR(hybrid_grid.GetProbability(Eigen::Array3i(1, 1, 1)), 0.42f, 1e-4);
00059 
00060   // Tests that further updates are ignored if FinishUpdate() isn't called.
00061   hybrid_grid.ApplyLookupTable(Eigen::Array3i(1, 1, 1),
00062                                ComputeLookupTableToApplyOdds(Odds(0.9f)));
00063   EXPECT_NEAR(hybrid_grid.GetProbability(Eigen::Array3i(1, 1, 1)), 0.42f, 1e-4);
00064   hybrid_grid.FinishUpdate();
00065   hybrid_grid.ApplyLookupTable(Eigen::Array3i(1, 1, 1),
00066                                ComputeLookupTableToApplyOdds(Odds(0.9f)));
00067   EXPECT_GT(hybrid_grid.GetProbability(Eigen::Array3i(1, 1, 1)), 0.42f);
00068 }
00069 
00070 TEST(HybridGridTest, GetProbability) {
00071   HybridGrid hybrid_grid(1.f);
00072 
00073   hybrid_grid.SetProbability(
00074       hybrid_grid.GetCellIndex(Eigen::Vector3f(0.f, 1.f, 1.f)),
00075       kMaxProbability);
00076   EXPECT_NEAR(hybrid_grid.GetProbability(
00077                   hybrid_grid.GetCellIndex(Eigen::Vector3f(0.f, 1.f, 1.f))),
00078               kMaxProbability, 1e-6);
00079   for (const Eigen::Array3i& index :
00080        {hybrid_grid.GetCellIndex(Eigen::Vector3f(0.f, 2.f, 1.f)),
00081         hybrid_grid.GetCellIndex(Eigen::Vector3f(1.f, 1.f, 1.f)),
00082         hybrid_grid.GetCellIndex(Eigen::Vector3f(1.f, 2.f, 1.f))}) {
00083     EXPECT_FALSE(hybrid_grid.IsKnown(index));
00084   }
00085 }
00086 
00087 MATCHER_P(AllCwiseEqual, index, "") { return (arg == index).all(); }
00088 
00089 TEST(HybridGridTest, GetCellIndex) {
00090   HybridGrid hybrid_grid(2.f);
00091 
00092   EXPECT_THAT(hybrid_grid.GetCellIndex(Eigen::Vector3f(0.f, 0.f, 0.f)),
00093               AllCwiseEqual(Eigen::Array3i(0, 0, 0)));
00094   EXPECT_THAT(hybrid_grid.GetCellIndex(Eigen::Vector3f(0.f, 26.f, 10.f)),
00095               AllCwiseEqual(Eigen::Array3i(0, 13, 5)));
00096   EXPECT_THAT(hybrid_grid.GetCellIndex(Eigen::Vector3f(14.f, 0.f, 10.f)),
00097               AllCwiseEqual(Eigen::Array3i(7, 0, 5)));
00098   EXPECT_THAT(hybrid_grid.GetCellIndex(Eigen::Vector3f(14.f, 26.f, 0.f)),
00099               AllCwiseEqual(Eigen::Array3i(7, 13, 0)));
00100 
00101   // Check around the origin.
00102   EXPECT_THAT(hybrid_grid.GetCellIndex(Eigen::Vector3f(8.5f, 11.5f, 0.5f)),
00103               AllCwiseEqual(Eigen::Array3i(4, 6, 0)));
00104   EXPECT_THAT(hybrid_grid.GetCellIndex(Eigen::Vector3f(7.5f, 12.5f, 1.5f)),
00105               AllCwiseEqual(Eigen::Array3i(4, 6, 1)));
00106   EXPECT_THAT(hybrid_grid.GetCellIndex(Eigen::Vector3f(6.5f, 14.5f, 2.5f)),
00107               AllCwiseEqual(Eigen::Array3i(3, 7, 1)));
00108   EXPECT_THAT(hybrid_grid.GetCellIndex(Eigen::Vector3f(5.5f, 13.5f, 3.5f)),
00109               AllCwiseEqual(Eigen::Array3i(3, 7, 2)));
00110 }
00111 
00112 TEST(HybridGridTest, GetCenterOfCell) {
00113   HybridGrid hybrid_grid(2.f);
00114 
00115   const Eigen::Array3i index(3, 2, 1);
00116   const Eigen::Vector3f center = hybrid_grid.GetCenterOfCell(index);
00117   EXPECT_NEAR(6.f, center.x(), 1e-6);
00118   EXPECT_NEAR(4.f, center.y(), 1e-6);
00119   EXPECT_NEAR(2.f, center.z(), 1e-6);
00120   EXPECT_THAT(hybrid_grid.GetCellIndex(center), AllCwiseEqual(index));
00121 }
00122 
00123 class RandomHybridGridTest : public ::testing::Test {
00124  public:
00125   RandomHybridGridTest() : hybrid_grid_(2.f), values_() {
00126     std::mt19937 rng(1285120005);
00127     std::uniform_real_distribution<float> value_distribution(kMinProbability,
00128                                                              kMaxProbability);
00129     std::uniform_int_distribution<int> xyz_distribution(-3000, 2999);
00130     for (int i = 0; i < 10000; ++i) {
00131       const auto x = xyz_distribution(rng);
00132       const auto y = xyz_distribution(rng);
00133       const auto z = xyz_distribution(rng);
00134       values_.emplace(std::make_tuple(x, y, z), value_distribution(rng));
00135     }
00136 
00137     for (const auto& pair : values_) {
00138       const Eigen::Array3i cell_index(std::get<0>(pair.first),
00139                                       std::get<1>(pair.first),
00140                                       std::get<2>(pair.first));
00141       hybrid_grid_.SetProbability(cell_index, pair.second);
00142     }
00143   }
00144 
00145  protected:
00146   HybridGrid hybrid_grid_;
00147   using ValueMap = std::map<std::tuple<int, int, int>, float>;
00148   ValueMap values_;
00149 };
00150 
00151 TEST_F(RandomHybridGridTest, TestIteration) {
00152   for (auto it = HybridGrid::Iterator(hybrid_grid_); !it.Done(); it.Next()) {
00153     const Eigen::Array3i cell_index = it.GetCellIndex();
00154     const float iterator_probability = ValueToProbability(it.GetValue());
00155     EXPECT_EQ(iterator_probability, hybrid_grid_.GetProbability(cell_index));
00156     const std::tuple<int, int, int> key =
00157         std::make_tuple(cell_index[0], cell_index[1], cell_index[2]);
00158     EXPECT_TRUE(values_.count(key));
00159     EXPECT_NEAR(values_[key], iterator_probability, 1e-4);
00160     values_.erase(key);
00161   }
00162 
00163   // Test that range based loop is equivalent to using the iterator.
00164   auto it = HybridGrid::Iterator(hybrid_grid_);
00165   for (const auto& cell : hybrid_grid_) {
00166     ASSERT_FALSE(it.Done());
00167     EXPECT_THAT(cell.first, AllCwiseEqual(it.GetCellIndex()));
00168     EXPECT_EQ(cell.second, it.GetValue());
00169     it.Next();
00170   }
00171 
00172   // Now 'values_' must not contain values.
00173   for (const auto& pair : values_) {
00174     const Eigen::Array3i cell_index(std::get<0>(pair.first),
00175                                     std::get<1>(pair.first),
00176                                     std::get<2>(pair.first));
00177     ADD_FAILURE() << cell_index << " Probability: " << pair.second;
00178   }
00179 }
00180 
00181 TEST_F(RandomHybridGridTest, ToProto) {
00182   const auto proto = hybrid_grid_.ToProto();
00183   EXPECT_EQ(hybrid_grid_.resolution(), proto.resolution());
00184   ASSERT_EQ(proto.x_indices_size(), proto.y_indices_size());
00185   ASSERT_EQ(proto.x_indices_size(), proto.z_indices_size());
00186   ASSERT_EQ(proto.x_indices_size(), proto.values_size());
00187 
00188   ValueMap proto_map;
00189   for (int i = 0; i < proto.x_indices_size(); ++i) {
00190     proto_map[std::make_tuple(proto.x_indices(i), proto.y_indices(i),
00191                               proto.z_indices(i))] = proto.values(i);
00192   }
00193 
00194   // Get hybrid_grid_ into the same format.
00195   ValueMap hybrid_grid_map;
00196   for (const auto i : hybrid_grid_) {
00197     hybrid_grid_map[std::make_tuple(i.first.x(), i.first.y(), i.first.z())] =
00198         i.second;
00199   }
00200 
00201   EXPECT_EQ(proto_map, hybrid_grid_map);
00202 }
00203 
00204 struct EigenComparator {
00205   bool operator()(const Eigen::Vector3i& lhs,
00206                   const Eigen::Vector3i& rhs) const {
00207     return std::forward_as_tuple(lhs.x(), lhs.y(), lhs.z()) <
00208            std::forward_as_tuple(rhs.x(), rhs.y(), rhs.z());
00209   }
00210 };
00211 
00212 TEST_F(RandomHybridGridTest, FromProto) {
00213   const HybridGrid constructed_grid(hybrid_grid_.ToProto());
00214 
00215   std::map<Eigen::Vector3i, float, EigenComparator> member_map(
00216       hybrid_grid_.begin(), hybrid_grid_.end());
00217 
00218   std::map<Eigen::Vector3i, float, EigenComparator> constructed_map(
00219       constructed_grid.begin(), constructed_grid.end());
00220 
00221   EXPECT_EQ(member_map, constructed_map);
00222 }
00223 
00224 }  // namespace
00225 }  // namespace mapping
00226 }  // namespace cartographer


cartographer
Author(s): The Cartographer Authors
autogenerated on Thu May 9 2019 02:27:35