forked from ANYbotics/grid_map
-
Notifications
You must be signed in to change notification settings - Fork 3
/
InterpolationDemo.cpp
354 lines (289 loc) · 11.4 KB
/
InterpolationDemo.cpp
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
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
/*
* InterpolationDemo.cpp
*
* Created on: Mar 16, 2020
* Author: Edo Jelavic
* Institute: ETH Zurich, Robotic Systems Lab
*/
#include "grid_map_demos/InterpolationDemo.hpp"
#include "grid_map_core/iterators/GridMapIterator.hpp"
#include "grid_map_msgs/GridMap.h"
#include "grid_map_ros/GridMapRosConverter.hpp"
namespace grid_map_demos {
AnalyticalFunctions createWorld(Worlds world, double highResolution, double lowResolution,
double length, double width, grid_map::GridMap *groundTruthHighRes,
grid_map::GridMap *groundTruthLowRes)
{
const grid_map::Length mapLength(length, width);
const grid_map::Position mapPosition(0.0, 0.0);
*groundTruthHighRes = createMap(mapLength, highResolution, mapPosition);
*groundTruthLowRes = createMap(mapLength, lowResolution, mapPosition);
AnalyticalFunctions groundTruth;
switch (world) {
case Worlds::Sine: {
groundTruth = createSineWorld(groundTruthHighRes);
createSineWorld(groundTruthLowRes);
break;
}
case Worlds::Tanh: {
groundTruth = createTanhWorld(groundTruthHighRes);
createTanhWorld(groundTruthLowRes);
break;
}
case Worlds::GaussMixture: {
groundTruth = createGaussianWorld(groundTruthHighRes);
createGaussianWorld(groundTruthLowRes);
break;
}
case Worlds::Poly: {
groundTruth = createPolyWorld(groundTruthHighRes);
createPolyWorld(groundTruthLowRes);
break;
}
default:
throw std::runtime_error("Interpolation demo: Unknown world requested.");
}
return groundTruth;
}
AnalyticalFunctions createPolyWorld(grid_map::GridMap *map)
{
AnalyticalFunctions func;
func.f_ = [](double x,double y) {
return (-x*x -y*y +2.0*x*y +x*x*y*y);
};
fillGridMap(map, func);
return func;
}
AnalyticalFunctions createSineWorld(grid_map::GridMap *map)
{
AnalyticalFunctions func;
const double w1 = 1.0;
const double w2 = 2.0;
const double w3 = 3.0;
const double w4 = 4.0;
func.f_ = [w1,w2,w3,w4](double x,double y) {
return std::cos(w1*x) + std::sin(w2*y) + std::cos(w3*x) + std::sin(w4*y);
};
fillGridMap(map, func);
return func;
}
AnalyticalFunctions createTanhWorld(grid_map::GridMap *map)
{
AnalyticalFunctions func;
const double s = 5.0;
func.f_ = [s](double x,double y) {
const double expZx = std::exp(2 *s* x);
const double tanX = (expZx - 1) / (expZx + 1);
const double expZy = std::exp(2 *s* y);
const double tanY = (expZy - 1) / (expZy + 1);
return tanX + tanY;
};
fillGridMap(map, func);
return func;
}
AnalyticalFunctions createGaussianWorld(grid_map::GridMap *map)
{
struct Gaussian
{
double x0, y0;
double varX, varY;
double s;
};
AnalyticalFunctions func;
constexpr int numGaussians = 7;
std::array<std::pair<double, double>, numGaussians> vars = { { { 1.0, 0.3 }, { 0.25, 0.25 }, {
0.1, 0.1 }, { 0.1, 0.1 }, { 0.1, 0.1 }, { 0.1, 0.05 }, { 0.05, 0.05 } } };
std::array<std::pair<double, double>, numGaussians> means = { { { 1, -1 }, { 1, 1.7 },
{ -1, 1.6 }, { -1.8, -1.8 }, { -1, 1.8 }, { 0, 0 }, { -1.2, 0 } } };
std::array<double, numGaussians> scales = { -2.0, -1.0, 2.0, 1.0, 3.0, 4.0, 1.0 };
std::array<Gaussian, numGaussians> g;
for (int i = 0; i < numGaussians; ++i) {
g.at(i).x0 = means.at(i).first;
g.at(i).y0 = means.at(i).second;
g.at(i).varX = vars.at(i).first;
g.at(i).varY = vars.at(i).second;
g.at(i).s = scales.at(i);
}
func.f_ = [g](double x,double y) {
double value = 0.0;
for (int i = 0; i < g.size(); ++i) {
const double x0 = g.at(i).x0;
const double y0 = g.at(i).y0;
const double varX = g.at(i).varX;
const double varY = g.at(i).varY;
const double s = g.at(i).s;
value += s * std::exp(-(x-x0)*(x-x0) / (2.0*varX) - (y-y0)*(y-y0) / (2.0 * varY));
}
return value;
};
fillGridMap(map, func);
return func;
}
void fillGridMap(grid_map::GridMap *map, const AnalyticalFunctions &functions)
{
grid_map::Matrix& data = (*map)[demoLayer];
for (grid_map::GridMapIterator iterator(*map); !iterator.isPastEnd(); ++iterator) {
const grid_map::Index index(*iterator);
grid_map::Position pos;
map->getPosition(index, pos);
data(index(0), index(1)) = functions.f_(pos.x(), pos.y());
}
}
grid_map::GridMap createMap(const grid_map::Length &length, double resolution,
const grid_map::Position &pos)
{
grid_map::GridMap map;
map.setGeometry(length, resolution, pos);
map.add(demoLayer, 0.0);
map.setFrameId("map");
return map;
}
grid_map::GridMap createInterpolatedMapFromDataMap(const grid_map::GridMap &dataMap,
double desiredResolution)
{
grid_map::GridMap interpolatedMap;
interpolatedMap.setGeometry(dataMap.getLength(), desiredResolution, dataMap.getPosition());
const std::string &layer = demoLayer;
interpolatedMap.add(layer, 0.0);
interpolatedMap.setFrameId(dataMap.getFrameId());
return interpolatedMap;
}
void interpolateInputMap(const grid_map::GridMap &dataMap,
grid_map::InterpolationMethods interpolationMethod,
grid_map::GridMap *interpolatedMap)
{
for (grid_map::GridMapIterator iterator(*interpolatedMap); !iterator.isPastEnd(); ++iterator) {
const grid_map::Index index(*iterator);
grid_map::Position pos;
interpolatedMap->getPosition(index, pos);
const double interpolatedHeight = dataMap.atPosition(demoLayer, pos, interpolationMethod);
interpolatedMap->at(demoLayer, index) = interpolatedHeight;
}
}
Error computeInterpolationError(const AnalyticalFunctions &groundTruth,
const grid_map::GridMap &map)
{
const double r = map.getResolution();
const double dimX = map.getLength().x() / 2.0 - 3.0 * r;
const double dimY = map.getLength().y() / 2.0 - 3.0 * r;
unsigned int count = 0;
Error error;
const int nRow = map.getSize().x();
const int nCol = map.getSize().y();
for (grid_map::GridMapIterator iterator(map); !iterator.isPastEnd(); ++iterator) {
const auto row = (*iterator).x();
const auto col = (*iterator).y();
const bool skipEvaluation = row < 2 || col < 2 || col > (nCol - 3) || row > (nRow - 3);
if (skipEvaluation) {
continue;
}
grid_map::Position pos;
map.getPosition(*iterator, pos);
const double f = map.at(demoLayer, *iterator);
const double f_ = groundTruth.f_(pos.x(), pos.y());
const double e = std::fabs(f - f_);
error.meanSquare_ += e * e;
error.meanAbs_ += e;
++count;
if (e > error.max_) {
error.max_ = e;
}
}
error.meanSquare_ /= count;
error.meanAbs_ /= count;
return error;
}
InterpolationDemo::InterpolationDemo(ros::NodeHandle *nh)
{
nh->param<std::string>("interpolation_type", interpolationMethod_, "Nearest");
nh->param<std::string>("world", world_, "Sine");
nh->param<double>("groundtruth_resolution", groundTruthResolution_, 0.02);
nh->param<double>("interpolation/data_resolution", dataResolution_, 0.1);
nh->param<double>("interpolation/interpolated_resolution", interpolatedResolution_, 0.02);
nh->param<double>("world_size/length", worldLength_, 4.0);
nh->param<double>("world_size/width", worldWidth_, 4.0);
groundTruthMapPub_ = nh->advertise<grid_map_msgs::GridMap>("ground_truth", 1, true);
dataSparseMapPub_ = nh->advertise<grid_map_msgs::GridMap>("data_sparse", 1, true);
interpolatedMapPub_ = nh->advertise<grid_map_msgs::GridMap>("interpolated", 1, true);
runDemo();
}
void InterpolationDemo::runDemo()
{
// visualize stuff
groundTruth_ = createWorld(worlds.at(world_), groundTruthResolution_, dataResolution_,
worldLength_, worldWidth_, &groundTruthMap_, &dataSparseMap_);
interpolatedMap_ = createInterpolatedMapFromDataMap(dataSparseMap_, interpolatedResolution_);
interpolateInputMap(dataSparseMap_, interpolationMethods.at(interpolationMethod_),
&interpolatedMap_);
publishGridMaps();
std::cout << "\n \n visualized the world: " << world_ << std::endl;
// print some info
const auto statistics = computeStatistics();
printStatistics(statistics);
}
InterpolationDemo::Statistics InterpolationDemo::computeStatistics() const
{
Statistics stats;
for (auto world = worlds.cbegin(); world != worlds.cend(); ++world) {
std::map<std::string, Statistic> methodsStats;
for (auto method = interpolationMethods.cbegin(); method != interpolationMethods.cend();
++method) {
const auto errorAndDuration = interpolateAndComputeError(world->first, method->first);
Statistic statistic;
statistic.duration_ = errorAndDuration.second;
statistic.error_ = errorAndDuration.first;
statistic.interpolationMethod_ = method->first;
statistic.world_ = world->first;
methodsStats.insert( { method->first, statistic });
}
stats.insert( { world->first, methodsStats });
}
return std::move(stats);
}
InterpolationDemo::ErrorAndDuration InterpolationDemo::interpolateAndComputeError(
const std::string world, const std::string &method) const
{
grid_map::GridMap highResMap, dataMap;
auto groundTruth = createWorld(worlds.at(world), groundTruthResolution_, dataResolution_,
worldLength_, worldWidth_, &highResMap, &dataMap);
auto interpolatedMap = createInterpolatedMapFromDataMap(dataMap, interpolatedResolution_);
const auto start = clk::now();
interpolateInputMap(dataMap, interpolationMethods.at(method), &interpolatedMap);
const auto end = clk::now();
const auto count = std::chrono::duration_cast<std::chrono::microseconds>(end - start).count();
const unsigned int numElements = interpolatedMap_.getSize().x() * interpolatedMap_.getSize().y();
ErrorAndDuration errorAndDuration;
errorAndDuration.first = computeInterpolationError(groundTruth, interpolatedMap);
errorAndDuration.second = static_cast<double>(count) / numElements;
return errorAndDuration;
}
void InterpolationDemo::printStatistics(const Statistics &stats) const
{
std::cout << " \n \n ================================== \n";
printf("Interpolated map of size: %f x %f \n", interpolatedMap_.getLength().x(),
interpolatedMap_.getLength().y());
printf("Resolution of the data: %f, resolution of the interpolated map: %f, \n \n",
dataSparseMap_.getResolution(), interpolatedMap_.getResolution());
for (auto world = worlds.cbegin(); world != worlds.cend(); ++world) {
std::cout << "Stats for the world: " << world->first << std::endl;
for (auto method = interpolationMethods.cbegin(); method != interpolationMethods.cend();
++method) {
Statistic s = stats.at(world->first).at(method->first);
printf(
"Method: %-20s Mean absolute error: %-10f max error: %-10f avg query duration: %-10f microsec \n",
method->first.c_str(), s.error_.meanAbs_, s.error_.max_, s.duration_);
}
std::cout << std::endl;
}
}
void InterpolationDemo::publishGridMaps() const
{
grid_map_msgs::GridMap highResMsg, lowResMsg, interpolatedMsg;
grid_map::GridMapRosConverter::toMessage(groundTruthMap_, highResMsg);
grid_map::GridMapRosConverter::toMessage(dataSparseMap_, lowResMsg);
grid_map::GridMapRosConverter::toMessage(interpolatedMap_, interpolatedMsg);
groundTruthMapPub_.publish(highResMsg);
dataSparseMapPub_.publish(lowResMsg);
interpolatedMapPub_.publish(interpolatedMsg);
}
} /* namespace grid_map_demos */