38 #include <gtest/gtest.h> 41 #include <opencv2/core/utility.hpp> 44 #define private public 53 "2011-08-09-12-22-52.pgm",
54 "2012-01-28-11-12-01.pgm",
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)) 65 TEST(MergingPipeline, canStich0Grid)
67 std::vector<nav_msgs::OccupancyGridConstPtr> maps;
69 merger.
feed(maps.begin(), maps.end());
75 TEST(MergingPipeline, canStich1Grid)
79 merger.
feed(&map, &map + 1);
85 EXPECT_TRUE(*merged_grid == *map);
88 EXPECT_EQ(transforms.size(), 1);
92 TEST(MergingPipeline, canStich2Grids)
96 merger.
feed(maps.begin(), maps.end());
97 merger.estimateTransforms();
98 auto merged_grid = merger.composeGrids();
102 EXPECT_NEAR(2091, merged_grid->info.width, 30);
103 EXPECT_NEAR(2091, merged_grid->info.height, 30);
106 saveMap(
"test_canStich2Grids.pgm", merged_grid);
110 TEST(MergingPipeline, canStichGridsGmapping)
114 merger.
feed(maps.begin(), maps.end());
115 merger.estimateTransforms();
116 auto merged_grid = merger.composeGrids();
120 EXPECT_NEAR(5427, merged_grid->info.width, 30);
121 EXPECT_NEAR(5427, merged_grid->info.height, 30);
124 saveMap(
"canStichGridsGmapping.pgm", merged_grid);
128 TEST(MergingPipeline, estimationAccuracy)
132 double angle = 0.523599 ;
136 cv::Matx23d transform{std::cos(angle), -std::sin(angle), tx,
137 std::sin(angle), std::cos(angle), ty};
141 merger.
feed(&map, &map + 1);
146 auto roi = warper.
warp(merger.
images_[0], cv::Mat(transform), warped);
150 merger.
grids_.emplace_back();
151 merger.
images_.push_back(warped);
159 EXPECT_EQ(transforms.size(), 2);
165 EXPECT_NEAR(tx - roi.tl().x, t.
getOrigin().x(), 2);
166 EXPECT_NEAR(ty - roi.tl().y, t.
getOrigin().y(), 2);
169 TEST(MergingPipeline, transformsRoundTrip)
173 merger.
feed(&map, &map + 1);
174 for (
size_t i = 0; i < 1000; ++i) {
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);
191 TEST(MergingPipeline, setTransformsInternal)
195 merger.
feed(&map, &map + 1);
197 for (
size_t i = 0; i < 1000; ++i) {
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}) {
210 cv::Mat p2 = transform_internal * cv::Mat(b[j]);
213 EXPECT_FLOAT_EQ(p1.x(), p2.at<
double>(0));
214 EXPECT_FLOAT_EQ(p1.y(), p2.at<
double>(1));
219 TEST(MergingPipeline, getTransformsInternal)
223 merger.
feed(&map, &map + 1);
227 for (
size_t i = 0; i < 1000; ++i) {
231 ASSERT_EQ(transforms.size(), 1);
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);
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));
250 TEST(MergingPipeline, setEmptyTransforms)
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());
263 TEST(MergingPipeline, emptyImageWithTransform)
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;
270 merger.
feed(maps.begin(), maps.end());
277 TEST(MergingPipeline, oneEmptyImage)
279 std::vector<nav_msgs::OccupancyGridConstPtr> maps{
nullptr,
282 merger.
feed(maps.begin(), maps.end());
289 EXPECT_TRUE(*merged_grid == *maps[1]);
291 EXPECT_EQ(transforms.size(), 2);
296 TEST(MergingPipeline, knownInitPositions)
300 merger.
feed(maps.begin(), maps.end());
302 for (
size_t i = 0; i < 5; ++i) {
305 merger.setTransforms(transforms.begin(), transforms.end());
306 auto merged_grid = merger.composeGrids();
312 int main(
int argc,
char** argv)
320 testing::InitGoogleTest(&argc, argv);
321 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
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)
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)
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()