InterpolationDemo.cpp
Go to the documentation of this file.
1 /*
2  * InterpolationDemo.cpp
3  *
4  * Created on: Mar 16, 2020
5  * Author: Edo Jelavic
6  * Institute: ETH Zurich, Robotic Systems Lab
7  */
8 
10 
12 #include "grid_map_msgs/GridMap.h"
14 
15 namespace grid_map_demos {
16 
17 AnalyticalFunctions createWorld(Worlds world, double highResolution, double lowResolution,
18  double length, double width, grid_map::GridMap *groundTruthHighRes,
19  grid_map::GridMap *groundTruthLowRes)
20 {
21 
22  const grid_map::Length mapLength(length, width);
23  const grid_map::Position mapPosition(0.0, 0.0);
24  *groundTruthHighRes = createMap(mapLength, highResolution, mapPosition);
25  *groundTruthLowRes = createMap(mapLength, lowResolution, mapPosition);
26  AnalyticalFunctions groundTruth;
27  switch (world) {
28 
29  case Worlds::Sine: {
30  groundTruth = createSineWorld(groundTruthHighRes);
31  createSineWorld(groundTruthLowRes);
32  break;
33  }
34  case Worlds::Tanh: {
35  groundTruth = createTanhWorld(groundTruthHighRes);
36  createTanhWorld(groundTruthLowRes);
37  break;
38  }
39  case Worlds::GaussMixture: {
40  groundTruth = createGaussianWorld(groundTruthHighRes);
41  createGaussianWorld(groundTruthLowRes);
42  break;
43  }
44  case Worlds::Poly: {
45  groundTruth = createPolyWorld(groundTruthHighRes);
46  createPolyWorld(groundTruthLowRes);
47  break;
48  }
49 
50  default:
51  throw std::runtime_error("Interpolation demo: Unknown world requested.");
52  }
53 
54  return groundTruth;
55 }
56 
58 {
59 
61 
62  func.f_ = [](double x,double y) {
63  return (-x*x -y*y +2.0*x*y +x*x*y*y);
64  };
65 
66  fillGridMap(map, func);
67 
68  return func;
69 
70 }
71 
73 {
74 
76 
77  const double w1 = 1.0;
78  const double w2 = 2.0;
79  const double w3 = 3.0;
80  const double w4 = 4.0;
81 
82  func.f_ = [w1,w2,w3,w4](double x,double y) {
83  return std::cos(w1*x) + std::sin(w2*y) + std::cos(w3*x) + std::sin(w4*y);
84  };
85 
86  fillGridMap(map, func);
87 
88  return func;
89 
90 }
91 
93 {
94 
96 
97  const double s = 5.0;
98  func.f_ = [s](double x,double y) {
99  const double expZx = std::exp(2 *s* x);
100  const double tanX = (expZx - 1) / (expZx + 1);
101  const double expZy = std::exp(2 *s* y);
102  const double tanY = (expZy - 1) / (expZy + 1);
103  return tanX + tanY;
104  };
105 
106  fillGridMap(map, func);
107 
108  return func;
109 }
110 
112 {
113 
114  struct Gaussian
115  {
116  double x0, y0;
117  double varX, varY;
118  double s;
119  };
120 
121  AnalyticalFunctions func;
122  constexpr int numGaussians = 7;
123  std::array<std::pair<double, double>, numGaussians> vars = { { { 1.0, 0.3 }, { 0.25, 0.25 }, {
124  0.1, 0.1 }, { 0.1, 0.1 }, { 0.1, 0.1 }, { 0.1, 0.05 }, { 0.05, 0.05 } } };
125  std::array<std::pair<double, double>, numGaussians> means = { { { 1, -1 }, { 1, 1.7 },
126  { -1, 1.6 }, { -1.8, -1.8 }, { -1, 1.8 }, { 0, 0 }, { -1.2, 0 } } };
127  std::array<double, numGaussians> scales = { -2.0, -1.0, 2.0, 1.0, 3.0, 4.0, 1.0 };
128 
129  std::array<Gaussian, numGaussians> g;
130 
131  for (int i = 0; i < numGaussians; ++i) {
132  g.at(i).x0 = means.at(i).first;
133  g.at(i).y0 = means.at(i).second;
134  g.at(i).varX = vars.at(i).first;
135  g.at(i).varY = vars.at(i).second;
136  g.at(i).s = scales.at(i);
137  }
138 
139  func.f_ = [g](double x,double y) {
140  double value = 0.0;
141  for (size_t i{0}; i < g.size(); ++i) {
142  const double x0 = g.at(i).x0;
143  const double y0 = g.at(i).y0;
144  const double varX = g.at(i).varX;
145  const double varY = g.at(i).varY;
146  const double s = g.at(i).s;
147  value += s * std::exp(-(x-x0)*(x-x0) / (2.0*varX) - (y-y0)*(y-y0) / (2.0 * varY));
148  }
149 
150  return value;
151  };
152 
153  fillGridMap(map, func);
154 
155  return func;
156 }
157 
159 {
160  grid_map::Matrix& data = (*map)[demoLayer];
161  for (grid_map::GridMapIterator iterator(*map); !iterator.isPastEnd(); ++iterator) {
162  const grid_map::Index index(*iterator);
163  grid_map::Position pos;
164  map->getPosition(index, pos);
165  data(index(0), index(1)) = functions.f_(pos.x(), pos.y());
166  }
167 }
168 
169 grid_map::GridMap createMap(const grid_map::Length &length, double resolution,
170  const grid_map::Position &pos)
171 {
172  grid_map::GridMap map;
173 
174  map.setGeometry(length, resolution, pos);
175  map.add(demoLayer, 0.0);
176  map.setFrameId("map");
177 
178  return map;
179 }
180 
182  double desiredResolution)
183 {
184  grid_map::GridMap interpolatedMap;
185  interpolatedMap.setGeometry(dataMap.getLength(), desiredResolution, dataMap.getPosition());
186  const std::string &layer = demoLayer;
187  interpolatedMap.add(layer, 0.0);
188  interpolatedMap.setFrameId(dataMap.getFrameId());
189 
190  return interpolatedMap;
191 }
192 
194  grid_map::InterpolationMethods interpolationMethod,
195  grid_map::GridMap *interpolatedMap)
196 {
197  for (grid_map::GridMapIterator iterator(*interpolatedMap); !iterator.isPastEnd(); ++iterator) {
198  const grid_map::Index index(*iterator);
199  grid_map::Position pos;
200  interpolatedMap->getPosition(index, pos);
201  const double interpolatedHeight = dataMap.atPosition(demoLayer, pos, interpolationMethod);
202  interpolatedMap->at(demoLayer, index) = interpolatedHeight;
203  }
204 }
205 
207  const grid_map::GridMap &map)
208 {
209  unsigned int count = 0;
210  Error error;
211  const int nRow = map.getSize().x();
212  const int nCol = map.getSize().y();
213  for (grid_map::GridMapIterator iterator(map); !iterator.isPastEnd(); ++iterator) {
214  const auto row = (*iterator).x();
215  const auto col = (*iterator).y();
216  const bool skipEvaluation = row < 2 || col < 2 || col > (nCol - 3) || row > (nRow - 3);
217  if (skipEvaluation) {
218  continue;
219  }
220  grid_map::Position pos;
221  map.getPosition(*iterator, pos);
222  const double f = map.at(demoLayer, *iterator);
223  const double f_ = groundTruth.f_(pos.x(), pos.y());
224  const double e = std::fabs(f - f_);
225  error.meanSquare_ += e * e;
226  error.meanAbs_ += e;
227  ++count;
228  if (e > error.max_) {
229  error.max_ = e;
230  }
231  }
232  error.meanSquare_ /= count;
233  error.meanAbs_ /= count;
234  return error;
235 
236 }
237 
239 {
240 
241  nh->param<std::string>("interpolation_type", interpolationMethod_, "Nearest");
242  nh->param<std::string>("world", world_, "Sine");
243  nh->param<double>("groundtruth_resolution", groundTruthResolution_, 0.02);
244  nh->param<double>("interpolation/data_resolution", dataResolution_, 0.1);
245  nh->param<double>("interpolation/interpolated_resolution", interpolatedResolution_, 0.02);
246  nh->param<double>("world_size/length", worldLength_, 4.0);
247  nh->param<double>("world_size/width", worldWidth_, 4.0);
248 
249  groundTruthMapPub_ = nh->advertise<grid_map_msgs::GridMap>("ground_truth", 1, true);
250  dataSparseMapPub_ = nh->advertise<grid_map_msgs::GridMap>("data_sparse", 1, true);
251  interpolatedMapPub_ = nh->advertise<grid_map_msgs::GridMap>("interpolated", 1, true);
252 
253  runDemo();
254 }
255 
257 {
258 
259  // visualize stuff
260  groundTruth_ = createWorld(worlds.at(world_), groundTruthResolution_, dataResolution_,
261  worldLength_, worldWidth_, &groundTruthMap_, &dataSparseMap_);
262 
263  interpolatedMap_ = createInterpolatedMapFromDataMap(dataSparseMap_, interpolatedResolution_);
264  interpolateInputMap(dataSparseMap_, interpolationMethods.at(interpolationMethod_),
265  &interpolatedMap_);
266 
267  publishGridMaps();
268  std::cout << "\n \n visualized the world: " << world_ << std::endl;
269 
270  // print some info
271  const auto statistics = computeStatistics();
272  printStatistics(statistics);
273 
274 }
275 
277 {
278  Statistics stats;
279  for (auto world = worlds.cbegin(); world != worlds.cend(); ++world) {
280  std::map<std::string, Statistic> methodsStats;
281  for (auto method = interpolationMethods.cbegin(); method != interpolationMethods.cend();
282  ++method) {
283  const auto errorAndDuration = interpolateAndComputeError(world->first, method->first);
284  Statistic statistic;
285  statistic.duration_ = errorAndDuration.second;
286  statistic.error_ = errorAndDuration.first;
287  statistic.interpolationMethod_ = method->first;
288  statistic.world_ = world->first;
289  methodsStats.insert( { method->first, statistic });
290  }
291  stats.insert( { world->first, methodsStats });
292  }
293 
294  return stats;
295 }
296 
298  const std::string world, const std::string &method) const
299 {
300  grid_map::GridMap highResMap, dataMap;
301  auto groundTruth = createWorld(worlds.at(world), groundTruthResolution_, dataResolution_,
302  worldLength_, worldWidth_, &highResMap, &dataMap);
303 
304  auto interpolatedMap = createInterpolatedMapFromDataMap(dataMap, interpolatedResolution_);
305  const auto start = clk::now();
306  interpolateInputMap(dataMap, interpolationMethods.at(method), &interpolatedMap);
307  const auto end = clk::now();
308  const auto count = std::chrono::duration_cast<std::chrono::microseconds>(end - start).count();
309  const unsigned int numElements = interpolatedMap_.getSize().x() * interpolatedMap_.getSize().y();
310 
311  ErrorAndDuration errorAndDuration;
312  errorAndDuration.first = computeInterpolationError(groundTruth, interpolatedMap);
313  errorAndDuration.second = static_cast<double>(count) / numElements;
314  return errorAndDuration;
315 }
316 
318 {
319  std::cout << " \n \n ================================== \n";
320  printf("Interpolated map of size: %f x %f \n", interpolatedMap_.getLength().x(),
321  interpolatedMap_.getLength().y());
322  printf("Resolution of the data: %f, resolution of the interpolated map: %f, \n \n",
323  dataSparseMap_.getResolution(), interpolatedMap_.getResolution());
324 
325  for (auto world = worlds.cbegin(); world != worlds.cend(); ++world) {
326  std::cout << "Stats for the world: " << world->first << std::endl;
327  for (auto method = interpolationMethods.cbegin(); method != interpolationMethods.cend();
328  ++method) {
329  Statistic s = stats.at(world->first).at(method->first);
330  printf(
331  "Method: %-20s Mean absolute error: %-10f max error: %-10f avg query duration: %-10f microsec \n",
332  method->first.c_str(), s.error_.meanAbs_, s.error_.max_, s.duration_);
333  }
334  std::cout << std::endl;
335  }
336 }
337 
339 {
340  grid_map_msgs::GridMap highResMsg, lowResMsg, interpolatedMsg;
341  grid_map::GridMapRosConverter::toMessage(groundTruthMap_, highResMsg);
342  grid_map::GridMapRosConverter::toMessage(dataSparseMap_, lowResMsg);
343  grid_map::GridMapRosConverter::toMessage(interpolatedMap_, interpolatedMsg);
344  groundTruthMapPub_.publish(highResMsg);
345  dataSparseMapPub_.publish(lowResMsg);
346  interpolatedMapPub_.publish(interpolatedMsg);
347 }
348 
349 } /* namespace grid_map_demos */
350 
const Length & getLength() const
AnalyticalFunctions createPolyWorld(grid_map::GridMap *map)
static const std::string demoLayer
AnalyticalFunctions createSineWorld(grid_map::GridMap *map)
Eigen::Array2i Index
void setGeometry(const Length &length, const double resolution, const Position &position=Position::Zero())
AnalyticalFunctions createWorld(Worlds world, double highResolution, double lowResolution, double length, double width, grid_map::GridMap *groundTruthHighRes, grid_map::GridMap *groundTruthLowRes)
float & atPosition(const std::string &layer, const Position &position)
f
std::map< std::string, std::map< std::string, Statistic > > Statistics
bool getPosition(const Index &index, Position &position) const
static const std::map< std::string, Worlds > worlds
std::pair< Error, double > ErrorAndDuration
ErrorAndDuration interpolateAndComputeError(const std::string world, const std::string &method) const
const std::string & getFrameId() const
XmlRpcServer s
Eigen::MatrixXf Matrix
static void toMessage(const grid_map::GridMap &gridMap, grid_map_msgs::GridMap &message)
TFSIMD_FORCE_INLINE const tfScalar & y() const
InterpolationMethods
void interpolateInputMap(const grid_map::GridMap &dataMap, grid_map::InterpolationMethods interpolationMethod, grid_map::GridMap *inteprolatedMap)
AnalyticalFunctions createGaussianWorld(grid_map::GridMap *map)
AnalyticalFunctions createTanhWorld(grid_map::GridMap *map)
std::function< double(double, double)> f_
Eigen::Vector2d Position
void fillGridMap(grid_map::GridMap *map, const AnalyticalFunctions &functions)
void printStatistics(const Statistics &stats) const
bool param(const std::string &param_name, T &param_val, const T &default_val) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
float & at(const std::string &layer, const Index &index)
void add(const std::string &layer, const double value=NAN)
Error computeInterpolationError(const AnalyticalFunctions &groundTruth, const grid_map::GridMap &map)
static const std::map< std::string, grid_map::InterpolationMethods > interpolationMethods
grid_map::GridMap createMap(const grid_map::Length &length, double resolution, const grid_map::Position &pos)
void setFrameId(const std::string &frameId)
grid_map::GridMap createInterpolatedMapFromDataMap(const grid_map::GridMap &dataMap, double desiredResolution)
Eigen::Array2d Length
const Size & getSize() const


grid_map_demos
Author(s): Péter Fankhauser
autogenerated on Tue Jun 1 2021 02:13:55