test_merging_pipeline.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015-2016, Jiri Horner.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the Jiri Horner nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  *********************************************************************/
36 
38 #include <gtest/gtest.h>
39 #include <ros/console.h>
41 #include <opencv2/core/utility.hpp>
42 #include "testing_helpers.h"
43 
44 #define private public
46 
47 const std::array<const char*, 2> hector_maps = {
48  "map00.pgm",
49  "map05.pgm",
50 };
51 
52 const std::array<const char*, 2> gmapping_maps = {
53  "2011-08-09-12-22-52.pgm",
54  "2012-01-28-11-12-01.pgm",
55 };
56 
57 constexpr bool verbose_tests = false;
58 
59 #define EXPECT_VALID_GRID(grid) \
60  ASSERT_TRUE(static_cast<bool>(grid)); \
61  EXPECT_TRUE(consistentData(*grid)); \
62  EXPECT_GT(grid->info.resolution, 0); \
63  EXPECT_TRUE(isIdentity(grid->info.origin.orientation))
64 
65 TEST(MergingPipeline, canStich0Grid)
66 {
67  std::vector<nav_msgs::OccupancyGridConstPtr> maps;
69  merger.feed(maps.begin(), maps.end());
70  EXPECT_TRUE(merger.estimateTransforms());
71  EXPECT_EQ(merger.composeGrids(), nullptr);
72  EXPECT_EQ(merger.getTransforms().size(), 0);
73 }
74 
75 TEST(MergingPipeline, canStich1Grid)
76 {
77  auto map = loadMap(hector_maps[1]);
79  merger.feed(&map, &map + 1);
80  merger.estimateTransforms();
81  auto merged_grid = merger.composeGrids();
82 
83  EXPECT_VALID_GRID(merged_grid);
84  // don't use EXPECT_EQ, since it prints too much info
85  EXPECT_TRUE(*merged_grid == *map);
86  // check estimated transforms
87  auto transforms = merger.getTransforms();
88  EXPECT_EQ(transforms.size(), 1);
89  EXPECT_TRUE(isIdentity(transforms[0]));
90 }
91 
92 TEST(MergingPipeline, canStich2Grids)
93 {
94  auto maps = loadMaps(hector_maps.begin(), hector_maps.end());
96  merger.feed(maps.begin(), maps.end());
97  merger.estimateTransforms();
98  auto merged_grid = merger.composeGrids();
99 
100  EXPECT_VALID_GRID(merged_grid);
101  // grid size should indicate sucessful merge
102  EXPECT_NEAR(2091, merged_grid->info.width, 30);
103  EXPECT_NEAR(2091, merged_grid->info.height, 30);
104 
105  if (verbose_tests) {
106  saveMap("test_canStich2Grids.pgm", merged_grid);
107  }
108 }
109 
110 TEST(MergingPipeline, canStichGridsGmapping)
111 {
112  auto maps = loadMaps(gmapping_maps.begin(), gmapping_maps.end());
114  merger.feed(maps.begin(), maps.end());
115  merger.estimateTransforms();
116  auto merged_grid = merger.composeGrids();
117 
118  EXPECT_VALID_GRID(merged_grid);
119  // grid size should indicate sucessful merge
120  EXPECT_NEAR(5427, merged_grid->info.width, 30);
121  EXPECT_NEAR(5427, merged_grid->info.height, 30);
122 
123  if (verbose_tests) {
124  saveMap("canStichGridsGmapping.pgm", merged_grid);
125  }
126 }
127 
128 TEST(MergingPipeline, estimationAccuracy)
129 {
130  // for this test we measure estimation on the same grid artificially
131  // transformed
132  double angle = 0.523599 /* 30 deg in rads*/;
133  // TODO test also translations
134  double tx = 0;
135  double ty = 0;
136  cv::Matx23d transform{std::cos(angle), -std::sin(angle), tx,
137  std::sin(angle), std::cos(angle), ty};
138 
139  auto map = loadMap(hector_maps[1]);
141  merger.feed(&map, &map + 1);
142 
143  // warp the map with Affine Transform
145  cv::Mat warped;
146  auto roi = warper.warp(merger.images_[0], cv::Mat(transform), warped);
147 
148  // add warped map
149  // this relies on internal implementation of merging pipeline
150  merger.grids_.emplace_back();
151  merger.images_.push_back(warped);
152 
153  merger.estimateTransforms();
154  auto merged_grid = merger.composeGrids();
155 
156  EXPECT_VALID_GRID(merged_grid);
157  // transforms
158  auto transforms = merger.getTransforms();
159  EXPECT_EQ(transforms.size(), 2);
160  EXPECT_TRUE(isIdentity(transforms[0]));
162  tf2::fromMsg(transforms[1], t);
163 
164  EXPECT_NEAR(angle, t.getRotation().getAngle(), 1e-2);
165  EXPECT_NEAR(tx - roi.tl().x, t.getOrigin().x(), 2);
166  EXPECT_NEAR(ty - roi.tl().y, t.getOrigin().y(), 2);
167 }
168 
169 TEST(MergingPipeline, transformsRoundTrip)
170 {
171  auto map = loadMap(hector_maps[0]);
173  merger.feed(&map, &map + 1);
174  for (size_t i = 0; i < 1000; ++i) {
175  auto in_transform = randomTransform();
176  merger.setTransforms(&in_transform, &in_transform + 1);
177 
178  auto out_transforms = merger.getTransforms();
179  ASSERT_EQ(out_transforms.size(), 1);
180  auto out_transform = out_transforms[0];
181  EXPECT_FLOAT_EQ(in_transform.translation.x, out_transform.translation.x);
182  EXPECT_FLOAT_EQ(in_transform.translation.y, out_transform.translation.y);
183  EXPECT_FLOAT_EQ(in_transform.translation.z, out_transform.translation.z);
184  EXPECT_FLOAT_EQ(in_transform.rotation.x, out_transform.rotation.x);
185  EXPECT_FLOAT_EQ(in_transform.rotation.y, out_transform.rotation.y);
186  EXPECT_FLOAT_EQ(in_transform.rotation.z, out_transform.rotation.z);
187  EXPECT_FLOAT_EQ(in_transform.rotation.w, out_transform.rotation.w);
188  }
189 }
190 
191 TEST(MergingPipeline, setTransformsInternal)
192 {
193  auto map = loadMap(hector_maps[0]);
195  merger.feed(&map, &map + 1);
196 
197  for (size_t i = 0; i < 1000; ++i) {
198  auto transform = randomTransform();
199  merger.setTransforms(&transform, &transform + 1);
200 
201  ASSERT_EQ(merger.transforms_.size(), 1);
202  auto& transform_internal = merger.transforms_[0];
203  // verify that transforms are the same in 2D
204  tf2::Vector3 a[2] = {{1., 0., 1.}, {0., 1., 1.}};
205  cv::Point3d b[2] = {{1., 0., 1.}, {0., 1., 1.}};
206  for (auto j : {0, 1}) {
208  fromMsg(transform, t);
209  auto p1 = t * a[j];
210  cv::Mat p2 = transform_internal * cv::Mat(b[j]);
211  // some precision is naturally lost during conversion, float precision is
212  // still good for us
213  EXPECT_FLOAT_EQ(p1.x(), p2.at<double>(0));
214  EXPECT_FLOAT_EQ(p1.y(), p2.at<double>(1));
215  }
216  }
217 }
218 
219 TEST(MergingPipeline, getTransformsInternal)
220 {
221  auto map = loadMap(hector_maps[0]);
223  merger.feed(&map, &map + 1);
224 
225  // set internal transform
226  merger.transforms_.resize(1);
227  for (size_t i = 0; i < 1000; ++i) {
228  cv::Mat transform_internal = randomTransformMatrix();
229  merger.transforms_[0] = transform_internal;
230  auto transforms = merger.getTransforms();
231  ASSERT_EQ(transforms.size(), 1);
232  // output quaternion should be normalized
233  auto& q = transforms[0].rotation;
234  EXPECT_DOUBLE_EQ(1., q.x * q.x + q.y * q.y + q.z * q.z + q.w * q.w);
235 
236  // verify that transforms are the same in 2D
237  tf2::Transform transform;
238  fromMsg(transforms[0], transform);
239  tf2::Vector3 a[2] = {{1., 0., 1.}, {0., 1., 1.}};
240  cv::Point3d b[2] = {{1., 0., 1.}, {0., 1., 1.}};
241  for (auto j : {0, 1}) {
242  auto p1 = transform * a[j];
243  cv::Mat p2 = transform_internal * cv::Mat(b[j]);
244  EXPECT_FLOAT_EQ(p1.x(), p2.at<double>(0));
245  EXPECT_FLOAT_EQ(p1.y(), p2.at<double>(1));
246  }
247  }
248 }
249 
250 TEST(MergingPipeline, setEmptyTransforms)
251 {
252  constexpr size_t size = 2;
253  std::vector<nav_msgs::OccupancyGridConstPtr> maps(size);
254  std::vector<geometry_msgs::Transform> transforms(size);
256  merger.feed(maps.begin(), maps.end());
257  merger.setTransforms(transforms.begin(), transforms.end());
258  EXPECT_EQ(merger.composeGrids(), nullptr);
259  EXPECT_EQ(merger.getTransforms().size(), size);
260 }
261 
262 /* empty image may end with identity transform. */
263 TEST(MergingPipeline, emptyImageWithTransform)
264 {
265  constexpr size_t size = 1;
266  std::vector<nav_msgs::OccupancyGridConstPtr> maps(size);
267  std::vector<geometry_msgs::Transform> transforms(size);
268  transforms[0].rotation.z = 1; // set transform to identity
270  merger.feed(maps.begin(), maps.end());
271  merger.setTransforms(transforms.begin(), transforms.end());
272  EXPECT_EQ(merger.composeGrids(), nullptr);
273  EXPECT_EQ(merger.getTransforms().size(), size);
274 }
275 
276 /* one image may be empty */
277 TEST(MergingPipeline, oneEmptyImage)
278 {
279  std::vector<nav_msgs::OccupancyGridConstPtr> maps{nullptr,
280  loadMap(gmapping_maps[0])};
282  merger.feed(maps.begin(), maps.end());
283  merger.estimateTransforms();
284  auto merged_grid = merger.composeGrids();
285  auto transforms = merger.getTransforms();
286 
287  EXPECT_VALID_GRID(merged_grid);
288  // don't use EXPECT_EQ, since it prints too much info
289  EXPECT_TRUE(*merged_grid == *maps[1]);
290  // transforms
291  EXPECT_EQ(transforms.size(), 2);
292  EXPECT_TRUE(isIdentity(transforms[1]));
293 }
294 
295 // non-identity known positions etc.
296 TEST(MergingPipeline, knownInitPositions)
297 {
298  auto maps = loadMaps(gmapping_maps.begin(), gmapping_maps.end());
300  merger.feed(maps.begin(), maps.end());
301 
302  for (size_t i = 0; i < 5; ++i) {
303  std::vector<geometry_msgs::Transform> transforms{randomTransform(),
304  randomTransform()};
305  merger.setTransforms(transforms.begin(), transforms.end());
306  auto merged_grid = merger.composeGrids();
307 
308  EXPECT_VALID_GRID(merged_grid);
309  }
310 }
311 
312 int main(int argc, char** argv)
313 {
314  ros::Time::init();
315  if (verbose_tests &&
319  }
320  testing::InitGoogleTest(&argc, argv);
321  return RUN_ALL_TESTS();
322 }
std::vector< cv::Mat > transforms_
std::vector< nav_msgs::OccupancyGridConstPtr > loadMaps(InputIt filenames_begin, InputIt filenames_end)
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
std::vector< cv::Mat > images_
TF2SIMD_FORCE_INLINE tf2Scalar angle(const Quaternion &q1, const Quaternion &q2)
nav_msgs::OccupancyGrid::Ptr composeGrids()
Pipeline for merging overlapping occupancy grids.
cv::Rect warp(const cv::Mat &grid, const cv::Mat &transform, cv::Mat &warped_grid)
Definition: grid_warper.cpp:47
cv::Mat randomTransformMatrix()
constexpr bool verbose_tests
geometry_msgs::TransformStamped t
tf2Scalar getAngle() const
nav_msgs::OccupancyGridConstPtr loadMap(const std::string &filename)
#define EXPECT_VALID_GRID(grid)
bool estimateTransforms(FeatureType feature=FeatureType::AKAZE, double confidence=1.0)
TF2SIMD_FORCE_INLINE Vector3 & getOrigin()
static void init()
void fromMsg(const A &, B &b)
bool setTransforms(InputIt transforms_begin, InputIt transforms_end)
static bool isIdentity(const cv::Mat &matrix)
void feed(InputIt grids_begin, InputIt grids_end)
void saveMap(const std::string &filename, const nav_msgs::OccupancyGridConstPtr &map)
Quaternion getRotation() const
std::vector< geometry_msgs::Transform > getTransforms() const
std::vector< nav_msgs::OccupancyGrid::ConstPtr > grids_
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
TEST(MergingPipeline, canStich0Grid)
#define ROSCONSOLE_DEFAULT_NAME
const std::array< const char *, 2 > gmapping_maps
const std::array< const char *, 2 > hector_maps
int main(int argc, char **argv)
geometry_msgs::Transform randomTransform()


map_merge
Author(s): Jiri Horner
autogenerated on Mon Feb 28 2022 22:46:02