-
Notifications
You must be signed in to change notification settings - Fork 872
Expand file tree
/
Copy pathGridMapCvTest.cpp
More file actions
167 lines (145 loc) · 5.43 KB
/
GridMapCvTest.cpp
File metadata and controls
167 lines (145 loc) · 5.43 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
/*
* GridMapCvTest.cpp
*
* Created on: Apr 14, 2016
* Author: Peter Fankhauser, Martin Wermelinger
* Institute: ETH Zurich, ANYbotics
*/
#include <grid_map_core/grid_map_core.hpp>
#include <grid_map_core/gtest_eigen.hpp>
// OpenCV
#include <cv_bridge/cv_bridge.hpp>
// gtest
#include <gtest/gtest.h>
#include <limits>
#include "grid_map_cv/grid_map_cv.hpp"
void replaceNan(grid_map::Matrix & m, const double newValue)
{
for(int r = 0; r < m.rows(); r++) {
for(int c = 0; c < m.cols(); c++) {
if (std::isnan(m(r, c))) {
m(r, c) = newValue;
}
}
}
}
TEST(ImageConversion, roundTrip8UC3)
{
// Create grid map.
grid_map::GridMap mapIn({"layer"});
mapIn.setGeometry(grid_map::Length(2.0, 1.0), 0.1);
mapIn["layer"].setRandom(); // Sets the layer to random values in [-1.0, 1.0].
mapIn.move(grid_map::Position(0.5, -0.2));
const float minValue = -1.0;
const float maxValue = 1.0;
// When we move `mapIn`, new areas are filled with NaN.
// As `toImage` does not support NaN, we replace NaN with `minValue` instead.
replaceNan(mapIn.get("layer"), minValue);
// Convert to image.
cv::Mat image;
grid_map::GridMapCvConverter::toImage<unsigned char, 3>(
mapIn, "layer", CV_8UC3, minValue,
maxValue, image);
// Convert back to grid map.
grid_map::GridMap mapOut(mapIn);
mapOut["layer"].setConstant(NAN);
grid_map::GridMapCvConverter::addLayerFromImage<unsigned char, 3>(
image, "layer", mapOut, minValue,
maxValue);
// Check data.
const float resolution = (maxValue - minValue) /
static_cast<float>(std::numeric_limits<unsigned char>::max());
grid_map::expectNear(mapIn["layer"], mapOut["layer"], resolution, "");
EXPECT_TRUE((mapIn.getLength() == mapOut.getLength()).all());
EXPECT_TRUE((mapIn.getSize() == mapOut.getSize()).all());
}
TEST(ImageConversion, roundTrip8UC4)
{
// Create grid map.
grid_map::GridMap mapIn({"layer"});
mapIn.setGeometry(grid_map::Length(2.0, 1.0), 0.1);
mapIn["layer"].setRandom(); // Sets the layer to random values in [-1.0, 1.0].
mapIn.move(grid_map::Position(0.5, -0.2));
const float minValue = -1.0;
const float maxValue = 1.0;
// When we move `mapIn`, new areas are filled with NaN.
// As `toImage` does not support NaN, we replace NaN with `minValue` instead.
replaceNan(mapIn.get("layer"), minValue);
// Convert to image.
cv::Mat image;
grid_map::GridMapCvConverter::toImage<unsigned char, 4>(
mapIn, "layer", CV_8UC4, minValue,
maxValue, image);
// Convert back to grid map.
grid_map::GridMap mapOut(mapIn);
mapOut["layer"].setConstant(NAN);
grid_map::GridMapCvConverter::addLayerFromImage<unsigned char, 4>(
image, "layer", mapOut, minValue,
maxValue);
// Check data.
const float resolution = (maxValue - minValue) /
static_cast<float>(std::numeric_limits<unsigned char>::max());
grid_map::expectNear(mapIn["layer"], mapOut["layer"], resolution, "");
EXPECT_TRUE((mapIn.getLength() == mapOut.getLength()).all());
EXPECT_TRUE((mapIn.getSize() == mapOut.getSize()).all());
}
TEST(ImageConversion, roundTrip16UC1)
{
// Create grid map.
grid_map::GridMap mapIn({"layer"});
mapIn.setGeometry(grid_map::Length(2.0, 1.0), 0.1);
mapIn["layer"].setRandom(); // Sets the layer to random values in [-1.0, 1.0].
mapIn.move(grid_map::Position(0.5, -0.2));
const float minValue = -1.0;
const float maxValue = 1.0;
// When we move `mapIn`, new areas are filled with NaN.
// As `toImage` does not support NaN, we replace NaN with `minValue` instead.
replaceNan(mapIn.get("layer"), minValue);
// Convert to image.
cv::Mat image;
grid_map::GridMapCvConverter::toImage<uint16_t, 1>(
mapIn, "layer", CV_16UC1, minValue, maxValue,
image);
// Convert back to grid map.
grid_map::GridMap mapOut(mapIn);
mapOut["layer"].setConstant(NAN);
grid_map::GridMapCvConverter::addLayerFromImage<uint16_t, 1>(
image, "layer", mapOut, minValue,
maxValue);
// Check data.
const float resolution = (maxValue - minValue) /
static_cast<float>(std::numeric_limits<unsigned char>::max());
grid_map::expectNear(mapIn["layer"], mapOut["layer"], resolution, "");
EXPECT_TRUE((mapIn.getLength() == mapOut.getLength()).all());
EXPECT_TRUE((mapIn.getSize() == mapOut.getSize()).all());
}
TEST(ImageConversion, roundTrip32FC1)
{
// Create grid map.
grid_map::GridMap mapIn({"layer"});
mapIn.setGeometry(grid_map::Length(2.0, 1.0), 0.1);
mapIn["layer"].setRandom(); // Sets the layer to random values in [-1.0, 1.0].
mapIn.move(grid_map::Position(0.5, -0.2));
const float minValue = -1.0;
const float maxValue = 1.0;
// When we move `mapIn`, new areas are filled with NaN.
// As `toImage` does not support NaN, we replace NaN with `minValue` instead.
replaceNan(mapIn.get("layer"), minValue);
// Convert to image.
cv::Mat image;
grid_map::GridMapCvConverter::toImage<float, 1>(
mapIn, "layer", CV_32FC1, minValue, maxValue,
image);
// Convert back to grid map.
grid_map::GridMap mapOut(mapIn);
mapOut["layer"].setConstant(NAN);
grid_map::GridMapCvConverter::addLayerFromImage<float, 1>(
image, "layer", mapOut, minValue,
maxValue);
// Check data.
const float resolution = (maxValue - minValue) /
static_cast<float>(std::numeric_limits<unsigned char>::max());
grid_map::expectNear(mapIn["layer"], mapOut["layer"], resolution, "");
EXPECT_TRUE((mapIn.getLength() == mapOut.getLength()).all());
EXPECT_TRUE((mapIn.getSize() == mapOut.getSize()).all());
}