38 #include <gtest/gtest.h> 41 #include <opencv2/core/utility.hpp> 44 #define private public 48 "map00.pgm",
"map05.pgm",
52 "2011-08-09-12-22-52.pgm",
"2012-01-28-11-12-01.pgm",
57 TEST(MergingPipeline, canStich0Grid)
59 std::vector<nav_msgs::OccupancyGridConstPtr> maps;
61 merger.
feed(maps.begin(), maps.end());
67 TEST(MergingPipeline, canStich1Grid)
71 merger.
feed(&map, &map + 1);
76 ASSERT_TRUE(static_cast<bool>(merged_grid));
77 EXPECT_FALSE(merged_grid->data.empty());
78 EXPECT_EQ((merged_grid->info.width) * (merged_grid->info.height),
79 merged_grid->data.size());
81 EXPECT_EQ(merged_grid->info.width, map->info.width);
82 EXPECT_EQ(merged_grid->info.height, map->info.height);
83 EXPECT_EQ(merged_grid->data.size(), map->data.size());
84 for (
size_t i = 0; i < merged_grid->data.size(); ++i) {
85 EXPECT_EQ(merged_grid->data[i], map->data[i]);
89 EXPECT_EQ(transforms.size(), 1);
95 TEST(MergingPipeline, canStich2Grids)
99 merger.
feed(maps.begin(), maps.end());
100 merger.estimateTransforms();
101 auto merged_grid = merger.composeGrids();
104 ASSERT_TRUE(static_cast<bool>(merged_grid));
105 EXPECT_FALSE(merged_grid->data.empty());
106 EXPECT_EQ((merged_grid->info.width) * (merged_grid->info.height),
107 merged_grid->data.size());
109 EXPECT_NEAR(2091, merged_grid->info.width, 30);
110 EXPECT_NEAR(2091, merged_grid->info.height, 30);
113 saveMap(
"test_canStich2Grids.pgm", merged_grid);
117 TEST(MergingPipeline, canStichGridsGmapping)
121 merger.
feed(maps.begin(), maps.end());
122 merger.estimateTransforms();
123 auto merged_grid = merger.composeGrids();
126 ASSERT_TRUE(static_cast<bool>(merged_grid));
127 EXPECT_FALSE(merged_grid->data.empty());
128 EXPECT_EQ((merged_grid->info.width) * (merged_grid->info.height),
129 merged_grid->data.size());
131 EXPECT_NEAR(5427, merged_grid->info.width, 30);
132 EXPECT_NEAR(5427, merged_grid->info.height, 30);
135 saveMap(
"canStichGridsGmapping.pgm", merged_grid);
139 TEST(MergingPipeline, estimationAccuracy)
143 double angle = 0.523599 ;
147 cv::Matx23d transform{std::cos(angle), -std::sin(angle), tx,
148 std::sin(angle), std::cos(angle), ty};
152 merger.
feed(&map, &map + 1);
157 auto roi = warper.
warp(merger.
images_[0], cv::Mat(transform), warped);
161 merger.
grids_.emplace_back();
162 merger.
images_.push_back(warped);
168 ASSERT_TRUE(static_cast<bool>(merged_grid));
169 EXPECT_FALSE(merged_grid->data.empty());
170 EXPECT_EQ((merged_grid->info.width) * (merged_grid->info.height),
171 merged_grid->data.size());
174 EXPECT_EQ(transforms.size(), 2);
180 EXPECT_NEAR(angle, t.getRotation().getAngle(), 1e-2);
181 EXPECT_NEAR(tx - roi.tl().x, t.getOrigin().x(), 2);
182 EXPECT_NEAR(ty - roi.tl().y, t.getOrigin().y(), 2);
185 TEST(MergingPipeline, transformsRoundTrip)
189 merger.
feed(&map, &map + 1);
190 for (
size_t i = 0; i < 1000; ++i) {
192 auto in_transform =
toMsg(
t);
195 if (in_transform.rotation.w < 0.) {
196 in_transform.rotation.x *= -1.;
197 in_transform.rotation.y *= -1.;
198 in_transform.rotation.z *= -1.;
199 in_transform.rotation.w *= -1.;
204 ASSERT_EQ(out_transforms.size(), 1);
205 auto out_transform = out_transforms[0];
206 EXPECT_FLOAT_EQ(in_transform.translation.x, out_transform.translation.x);
207 EXPECT_FLOAT_EQ(in_transform.translation.y, out_transform.translation.y);
208 EXPECT_FLOAT_EQ(in_transform.translation.z, out_transform.translation.z);
209 EXPECT_FLOAT_EQ(in_transform.rotation.x, out_transform.rotation.x);
210 EXPECT_FLOAT_EQ(in_transform.rotation.y, out_transform.rotation.y);
211 EXPECT_FLOAT_EQ(in_transform.rotation.z, out_transform.rotation.z);
212 EXPECT_FLOAT_EQ(in_transform.rotation.w, out_transform.rotation.w);
216 TEST(MergingPipeline, setTransformsInternal)
220 merger.
feed(&map, &map + 1);
222 for (
size_t i = 0; i < 1000; ++i) {
224 geometry_msgs::Transform
t =
toMsg(transform);
230 tf2::Vector3 a[2] = {{1., 0., 1.}, {0., 1., 1.}};
231 cv::Point3d b[2] = {{1., 0., 1.}, {0., 1., 1.}};
232 for (
auto j : {0, 1}) {
233 auto p1 = transform * a[j];
234 cv::Mat p2 = transform_internal * cv::Mat(b[j]);
237 EXPECT_FLOAT_EQ(p1.x(), p2.at<
double>(0));
238 EXPECT_FLOAT_EQ(p1.y(), p2.at<
double>(1));
243 TEST(MergingPipeline, getTransformsInternal)
247 merger.
feed(&map, &map + 1);
251 for (
size_t i = 0; i < 1000; ++i) {
255 ASSERT_EQ(transforms.size(), 1);
257 auto& q = transforms[0].rotation;
258 EXPECT_DOUBLE_EQ(1., q.x * q.x + q.y * q.y + q.z * q.z + q.w * q.w);
262 fromMsg(transforms[0], transform);
263 tf2::Vector3 a[2] = {{1., 0., 1.}, {0., 1., 1.}};
264 cv::Point3d b[2] = {{1., 0., 1.}, {0., 1., 1.}};
265 for (
auto j : {0, 1}) {
266 auto p1 = transform * a[j];
267 cv::Mat p2 = transform_internal * cv::Mat(b[j]);
268 EXPECT_FLOAT_EQ(p1.x(), p2.at<
double>(0));
269 EXPECT_FLOAT_EQ(p1.y(), p2.at<
double>(1));
274 TEST(MergingPipeline, setEmptyTransforms)
276 constexpr
size_t size = 2;
277 std::vector<nav_msgs::OccupancyGridConstPtr> maps(size);
278 std::vector<geometry_msgs::Transform> transforms(size);
280 merger.
feed(maps.begin(), maps.end());
287 TEST(MergingPipeline, emptyImageWithTransform)
289 constexpr
size_t size = 1;
290 std::vector<nav_msgs::OccupancyGridConstPtr> maps(size);
291 std::vector<geometry_msgs::Transform> transforms(size);
292 transforms[0].rotation.z = 1;
294 merger.
feed(maps.begin(), maps.end());
300 int main(
int argc,
char** argv)
308 testing::InitGoogleTest(&argc, argv);
309 return RUN_ALL_TESTS();
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)
cv::Mat randomTransformMatrix()
constexpr bool verbose_tests
std::vector< geometry_msgs::Transform > getTransforms() const
geometry_msgs::TransformStamped t
nav_msgs::OccupancyGridConstPtr loadMap(const std::string &filename)
bool estimateTransforms(FeatureType feature=FeatureType::AKAZE, double confidence=1.0)
void fromMsg(const A &, B &b)
bool setTransforms(InputIt transforms_begin, InputIt transforms_end)
void feed(InputIt grids_begin, InputIt grids_end)
void saveMap(const std::string &filename, const nav_msgs::OccupancyGridConstPtr &map)
std::vector< nav_msgs::OccupancyGrid::ConstPtr > grids_
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
TEST(MergingPipeline, canStich0Grid)
tf2::Transform randomTransform()
#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)