GridMap.cpp
Go to the documentation of this file.
1 /*
2  * GridMap.cpp
3  *
4  * Created on: Jul 14, 2014
5  * Author: Péter Fankhauser
6  * Institute: ETH Zurich, ANYbotics
7  */
8 
10 
15 
16 #include <cmath>
17 #include <algorithm>
18 #include <cassert>
19 #include <iostream>
20 #include <stdexcept>
21 
22 using std::cout;
23 using std::endl;
24 using std::isfinite;
25 
26 namespace grid_map {
27 
28 GridMap::GridMap(const std::vector<std::string>& layers) {
29  position_.setZero();
30  length_.setZero();
31  resolution_ = 0.0;
32  size_.setZero();
33  startIndex_.setZero();
34  timestamp_ = 0;
35  layers_ = layers;
36 
37  for (auto& layer : layers_) {
38  data_.insert(std::pair<std::string, Matrix>(layer, Matrix()));
39  }
40 }
41 
42 GridMap::GridMap() : GridMap(std::vector<std::string>()) {}
43 
44 void GridMap::setGeometry(const Length& length, const double resolution, const Position& position) {
45  assert(length(0) > 0.0);
46  assert(length(1) > 0.0);
47  assert(resolution > 0.0);
48 
49  Size size;
50  size(0) = static_cast<int>(round(length(0) / resolution)); // There is no round() function in Eigen.
51  size(1) = static_cast<int>(round(length(1) / resolution));
52  resize(size);
53  clearAll();
54 
55  resolution_ = resolution;
56  length_ = (size_.cast<double>() * resolution_).matrix();
57  position_ = position;
58  startIndex_.setZero();
59 }
60 
61 void GridMap::setGeometry(const SubmapGeometry& geometry) {
62  setGeometry(geometry.getLength(), geometry.getResolution(), geometry.getPosition());
63 }
64 
65 void GridMap::setBasicLayers(const std::vector<std::string>& basicLayers) {
66  basicLayers_ = basicLayers;
67 }
68 
69 const std::vector<std::string>& GridMap::getBasicLayers() const {
70  return basicLayers_;
71 }
72 
74  return !basicLayers_.empty();
75 }
76 
77 bool GridMap::hasSameLayers(const GridMap& other) const {
78  return std::all_of(layers_.begin(), layers_.end(),
79  [&](const std::string& layer){return other.exists(layer);});
80 }
81 
82 void GridMap::add(const std::string& layer, const double value) {
83  add(layer, Matrix::Constant(size_(0), size_(1), value));
84 }
85 
86 void GridMap::add(const std::string& layer, const Matrix& data) {
87  assert(size_(0) == data.rows());
88  assert(size_(1) == data.cols());
89 
90  if (exists(layer)) {
91  // Type exists already, overwrite its data.
92  data_.at(layer) = data;
93  } else {
94  // Type does not exist yet, add type and data.
95  data_.insert(std::pair<std::string, Matrix>(layer, data));
96  layers_.push_back(layer);
97  }
98 }
99 
100 bool GridMap::exists(const std::string& layer) const {
101  return !(data_.find(layer) == data_.end());
102 }
103 
104 const Matrix& GridMap::get(const std::string& layer) const {
105  try {
106  return data_.at(layer);
107  } catch (const std::out_of_range& exception) {
108  throw std::out_of_range("GridMap::get(...) : No map layer '" + layer + "' available.");
109  }
110 }
111 
112 Matrix& GridMap::get(const std::string& layer) {
113  try {
114  return data_.at(layer);
115  } catch (const std::out_of_range& exception) {
116  throw std::out_of_range("GridMap::get(...) : No map layer of type '" + layer + "' available.");
117  }
118 }
119 
120 const Matrix& GridMap::operator[](const std::string& layer) const {
121  return get(layer);
122 }
123 
124 Matrix& GridMap::operator[](const std::string& layer) {
125  return get(layer);
126 }
127 
128 bool GridMap::erase(const std::string& layer) {
129  const auto dataIterator = data_.find(layer);
130  if (dataIterator == data_.end()) {
131  return false;
132  }
133  data_.erase(dataIterator);
134 
135  const auto layerIterator = std::find(layers_.begin(), layers_.end(), layer);
136  if (layerIterator == layers_.end()) {
137  return false;
138  }
139  layers_.erase(layerIterator);
140 
141  const auto basicLayerIterator = std::find(basicLayers_.begin(), basicLayers_.end(), layer);
142  if (basicLayerIterator != basicLayers_.end()) {
143  basicLayers_.erase(basicLayerIterator);
144  }
145 
146  return true;
147 }
148 
149 const std::vector<std::string>& GridMap::getLayers() const {
150  return layers_;
151 }
152 
153 float& GridMap::atPosition(const std::string& layer, const Position& position) {
154  Index index;
155  if (getIndex(position, index)) {
156  return at(layer, index);
157  }
158  throw std::out_of_range("GridMap::atPosition(...) : Position is out of range.");
159 }
160 
161 float GridMap::atPosition(const std::string& layer, const Position& position, InterpolationMethods interpolationMethod) const {
162 
163  bool skipNextSwitchCase = false;
164  switch (interpolationMethod) {
166  float value;
167  if (atPositionBicubicConvolutionInterpolated(layer, position, value)) {
168  return value;
169  } else {
170  interpolationMethod = InterpolationMethods::INTER_LINEAR;
171  skipNextSwitchCase = true;
172  }
173  [[fallthrough]];
174  }
176  if (!skipNextSwitchCase) {
177  float value;
178  if (atPositionBicubicInterpolated(layer, position, value)) {
179  return value;
180  } else {
181  interpolationMethod = InterpolationMethods::INTER_LINEAR;
182  }
183  }
184  [[fallthrough]];
185  }
187  float value;
188  if (atPositionLinearInterpolated(layer, position, value)){
189  return value;
190  }
191  else {
192  interpolationMethod = InterpolationMethods::INTER_NEAREST;
193  }
194  [[fallthrough]];
195  }
197  Index index;
198  if (getIndex(position, index)) {
199  return at(layer, index);
200  } else {
201  throw std::out_of_range("GridMap::atPosition(...) : Position is out of range.");
202  }
203  break;
204  }
205  default:
206  throw std::runtime_error(
207  "GridMap::atPosition(...) : Specified "
208  "interpolation method not implemented.");
209  }
210 }
211 
212 float& GridMap::at(const std::string& layer, const Index& index) {
213  try {
214  return data_.at(layer)(index(0), index(1));
215  } catch (const std::out_of_range& exception) {
216  throw std::out_of_range("GridMap::at(...) : No map layer '" + layer + "' available.");
217  }
218 }
219 
220 float GridMap::at(const std::string& layer, const Index& index) const {
221  try {
222  return data_.at(layer)(index(0), index(1));
223  } catch (const std::out_of_range& exception) {
224  throw std::out_of_range("GridMap::at(...) : No map layer '" + layer + "' available.");
225  }
226 }
227 
228 bool GridMap::getIndex(const Position& position, Index& index) const {
229  return getIndexFromPosition(index, position, length_, position_, resolution_, size_, startIndex_);
230 }
231 
232 bool GridMap::getPosition(const Index& index, Position& position) const {
233  return getPositionFromIndex(position, index, length_, position_, resolution_, size_, startIndex_);
234 }
235 
236 bool GridMap::isInside(const Position& position) const {
237  return checkIfPositionWithinMap(position, length_, position_);
238 }
239 
240 bool GridMap::isValid(DataType value) const {
241  return isfinite(value);
242 }
243 
244 bool GridMap::isValid(const Index& index) const {
245  return isValid(index, basicLayers_);
246 }
247 
248 bool GridMap::isValid(const Index& index, const std::string& layer) const {
249  return isValid(at(layer, index));
250 }
251 
252 bool GridMap::isValid(const Index& index, const std::vector<std::string>& layers) const {
253  if (layers.empty()) {
254  return false;
255  }
256  return std::all_of(layers.begin(), layers.end(),
257  [&](const std::string& layer){return isValid(index, layer);});
258 }
259 
260 bool GridMap::getPosition3(const std::string& layer, const Index& index, Position3& position) const {
261  const auto value = at(layer, index);
262  if (!isValid(value)) {
263  return false;
264  }
265  Position position2d;
266  getPosition(index, position2d);
267  position.head(2) = position2d;
268  position.z() = value;
269  return true;
270 }
271 
272 bool GridMap::getVector(const std::string& layerPrefix, const Index& index, Eigen::Vector3d& vector) const {
273  Eigen::Vector3d temp{at(layerPrefix + "x", index), at(layerPrefix + "y", index), at(layerPrefix + "z", index)};
274  if (!isValid(temp[0]) || !isValid(temp[1]) || !isValid(temp[2])) {
275  return false;
276  } else {
277  vector = temp;
278  return true;
279  }
280 }
281 
282 GridMap GridMap::getSubmap(const Position& position, const Length& length, bool& isSuccess) const {
283  Index index;
284  return getSubmap(position, length, index, isSuccess);
285 }
286 
287 GridMap GridMap::getSubmap(const Position& position, const Length& length, Index& /*indexInSubmap*/, bool& isSuccess) const {
288  // Submap to generate.
289  GridMap submap(layers_);
291  submap.setTimestamp(timestamp_);
292  submap.setFrameId(frameId_);
293 
294  // Get submap geometric information.
295  SubmapGeometry submapInformation(*this, position, length, isSuccess);
296  if (!isSuccess) {
297  return {layers_};
298  }
299  submap.setGeometry(submapInformation);
300  submap.startIndex_.setZero(); // Because of the way we copy the data below.
301 
302  // Copy data.
303  std::vector<BufferRegion> bufferRegions;
304 
305  if (!getBufferRegionsForSubmap(bufferRegions, submapInformation.getStartIndex(), submap.getSize(), size_, startIndex_)) {
306  cout << "Cannot access submap of this size." << endl;
307  isSuccess = false;
308  return {layers_};
309  }
310 
311  for (const auto& data : data_) {
312  for (const auto& bufferRegion : bufferRegions) {
313  Index index = bufferRegion.getStartIndex();
314  Size size = bufferRegion.getSize();
315 
316  if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::TopLeft) {
317  submap.data_[data.first].topLeftCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
318  } else if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::TopRight) {
319  submap.data_[data.first].topRightCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
320  } else if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::BottomLeft) {
321  submap.data_[data.first].bottomLeftCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
322  } else if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::BottomRight) {
323  submap.data_[data.first].bottomRightCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
324  }
325  }
326  }
327 
328  isSuccess = true;
329  return submap;
330 }
331 
332 GridMap GridMap::getTransformedMap(const Eigen::Isometry3d& transform, const std::string& heightLayerName, const std::string& newFrameId,
333  const double sampleRatio) const {
334  // Check if height layer is valid.
335  if (!exists(heightLayerName)) {
336  throw std::out_of_range("GridMap::getTransformedMap(...) : No map layer '" + heightLayerName + "' available.");
337  }
338 
339  // Initialization.
340  std::vector<Position3> positionSamples;
341  Position3 center;
342  Index newIndex;
343 
344  const double sampleLength = resolution_ * sampleRatio;
345 
346  // Find edges in new coordinate frame.
347  const double halfLengthX = length_.x() * 0.5;
348  const double halfLengthY = length_.y() * 0.5;
349  const Position3 topLeftCorner(position_.x() + halfLengthX, position_.y() + halfLengthY, 0.0);
350  const Position3 topRightCorner(position_.x() + halfLengthX, position_.y() - halfLengthY, 0.0);
351  const Position3 bottomLeftCorner(position_.x() - halfLengthX, position_.y() + halfLengthY, 0.0);
352  const Position3 bottomRightCorner(position_.x() - halfLengthX, position_.y() - halfLengthY, 0.0);
353 
354  std::vector<Position3> newEdges;
355  newEdges.reserve(4);
356  newEdges.push_back(transform * topLeftCorner);
357  newEdges.push_back(transform * topRightCorner);
358  newEdges.push_back(transform * bottomLeftCorner);
359  newEdges.push_back(transform * bottomRightCorner);
360 
361  // Find new grid center.
362  Position3 newCenter = Position3::Zero();
363  for (const auto& newEdge : newEdges) {
364  newCenter += newEdge;
365  }
366  newCenter *= 0.25;
367 
368  // Find new grid length.
369  Length maxLengthFromCenter = Length(0.0, 0.0);
370  for (const auto& newEdge : newEdges) {
371  Position3 positionCenterToEdge = newEdge - newCenter;
372  maxLengthFromCenter.x() = std::fmax(std::fabs(positionCenterToEdge.x()), maxLengthFromCenter.x());
373  maxLengthFromCenter.y() = std::fmax(std::fabs(positionCenterToEdge.y()), maxLengthFromCenter.y());
374  }
375  Length newLength = 2.0 * maxLengthFromCenter;
376 
377  // Create new grid map.
378  GridMap newMap(layers_);
380  newMap.setTimestamp(timestamp_);
381  newMap.setFrameId(newFrameId);
382  newMap.setGeometry(newLength, resolution_, Position(newCenter.x(), newCenter.y()));
383  newMap.startIndex_.setZero();
384 
385  for (GridMapIterator iterator(*this); !iterator.isPastEnd(); ++iterator) {
386  // Get position at current index.
387  if (!getPosition3(heightLayerName, *iterator, center)) {
388  continue;
389  }
390 
391  // Sample four points around the center cell.
392  positionSamples.clear();
393 
394  if (sampleRatio > 0.0) {
395  positionSamples.reserve(5);
396  positionSamples.push_back(center);
397  positionSamples.emplace_back(center.x() - sampleLength, center.y(), center.z());
398  positionSamples.emplace_back(center.x() + sampleLength, center.y(), center.z());
399  positionSamples.emplace_back(center.x(), center.y() - sampleLength, center.z());
400  positionSamples.emplace_back(center.x(), center.y() + sampleLength, center.z());
401  } else {
402  positionSamples.push_back(center);
403  }
404 
405  // Transform the sampled points and register to the new map.
406  for (const auto& position : positionSamples) {
407  const Position3 transformedPosition = transform * position;
408 
409  // Get new index.
410  if (!newMap.getIndex(Position(transformedPosition.x(), transformedPosition.y()), newIndex)) {
411  continue;
412  }
413 
414  // Check if we have already assigned a value (preferably larger height
415  // values -> inpainting).
416  const auto newExistingValue = newMap.at(heightLayerName, newIndex);
417  if (!std::isnan(newExistingValue) && newExistingValue > transformedPosition.z()) {
418  continue;
419  }
420 
421  // Copy the layers.
422  for (const auto& layer : layers_) {
423  const auto currentValueInOldGrid = at(layer, *iterator);
424  auto& newValue = newMap.at(layer, newIndex);
425  if (layer == heightLayerName) {
426  newValue = transformedPosition.z();
427  } // adjust height
428  else {
429  newValue = currentValueInOldGrid;
430  } // re-assign
431  }
432  }
433  }
434 
435  return newMap;
436 }
437 
438 void GridMap::setPosition(const Position& position) {
439  position_ = position;
440 }
441 
442 bool GridMap::move(const Position& position, std::vector<BufferRegion>& newRegions) {
443  Index indexShift;
444  Position positionShift = position - position_;
445  getIndexShiftFromPositionShift(indexShift, positionShift, resolution_);
446  Position alignedPositionShift;
447  getPositionShiftFromIndexShift(alignedPositionShift, indexShift, resolution_);
448 
449  // Delete fields that fall out of map (and become empty cells).
450  for (int i = 0; i < indexShift.size(); i++) {
451  if (indexShift(i) != 0) {
452  if (abs(indexShift(i)) >= getSize()(i)) {
453  // Entire map is dropped.
454  clearAll();
455  newRegions.emplace_back(Index(0, 0), getSize(), BufferRegion::Quadrant::Undefined);
456  } else {
457  // Drop cells out of map.
458  int sign = (indexShift(i) > 0 ? 1 : -1);
459  int startIndex = startIndex_(i) - (sign < 0 ? 1 : 0);
460  int endIndex = startIndex - sign + indexShift(i);
461  int nCells = abs(indexShift(i));
462  int index = (sign > 0 ? startIndex : endIndex);
463  wrapIndexToRange(index, getSize()(i));
464 
465  if (index + nCells <= getSize()(i)) {
466  // One region to drop.
467  if (i == 0) {
468  clearRows(index, nCells);
469  newRegions.emplace_back(Index(index, 0), Size(nCells, getSize()(1)), BufferRegion::Quadrant::Undefined);
470  } else if (i == 1) {
471  clearCols(index, nCells);
472  newRegions.emplace_back(Index(0, index), Size(getSize()(0), nCells), BufferRegion::Quadrant::Undefined);
473  }
474  } else {
475  // Two regions to drop.
476  int firstIndex = index;
477  int firstNCells = getSize()(i) - firstIndex;
478  if (i == 0) {
479  clearRows(firstIndex, firstNCells);
480  newRegions.emplace_back(Index(firstIndex, 0), Size(firstNCells, getSize()(1)), BufferRegion::Quadrant::Undefined);
481  } else if (i == 1) {
482  clearCols(firstIndex, firstNCells);
483  newRegions.emplace_back(Index(0, firstIndex), Size(getSize()(0), firstNCells), BufferRegion::Quadrant::Undefined);
484  }
485 
486  int secondIndex = 0;
487  int secondNCells = nCells - firstNCells;
488  if (i == 0) {
489  clearRows(secondIndex, secondNCells);
490  newRegions.emplace_back(Index(secondIndex, 0), Size(secondNCells, getSize()(1)), BufferRegion::Quadrant::Undefined);
491  } else if (i == 1) {
492  clearCols(secondIndex, secondNCells);
493  newRegions.emplace_back(Index(0, secondIndex), Size(getSize()(0), secondNCells), BufferRegion::Quadrant::Undefined);
494  }
495  }
496  }
497  }
498  }
499 
500  // Update information.
501  startIndex_ += indexShift;
503  position_ += alignedPositionShift;
504 
505  // Check if map has been moved at all.
506  return indexShift.any();
507 }
508 
509 bool GridMap::move(const Position& position) {
510  std::vector<BufferRegion> newRegions;
511  return move(position, newRegions);
512 }
513 
514 bool GridMap::addDataFrom(const GridMap& other, bool extendMap, bool overwriteData, bool copyAllLayers, std::vector<std::string> layers) {
515  // Set the layers to copy.
516  if (copyAllLayers) {
517  layers = other.getLayers();
518  }
519 
520  // Resize map.
521  if (extendMap) {
522  extendToInclude(other);
523  }
524 
525  // Check if all layers to copy exist and add missing layers.
526  for (const auto& layer : layers) {
527  if (std::find(layers_.begin(), layers_.end(), layer) == layers_.end()) {
528  add(layer);
529  }
530  }
531  // Copy data.
532  for (GridMapIterator iterator(*this); !iterator.isPastEnd(); ++iterator) {
533  if (isValid(*iterator) && !overwriteData) {
534  continue;
535  }
536  Position position;
537  getPosition(*iterator, position);
538  Index index;
539  if (!other.isInside(position)) {
540  continue;
541  }
542  other.getIndex(position, index);
543  for (const auto& layer : layers) {
544  if (!other.isValid(index, layer)) {
545  continue;
546  }
547  at(layer, *iterator) = other.at(layer, index);
548  }
549  }
550 
551  return true;
552 }
553 
554 bool GridMap::extendToInclude(const GridMap& other) {
555  // Get dimension of maps.
556  Position topLeftCorner(position_.x() + length_.x() / 2.0, position_.y() + length_.y() / 2.0);
557  Position bottomRightCorner(position_.x() - length_.x() / 2.0, position_.y() - length_.y() / 2.0);
558  Position topLeftCornerOther(other.getPosition().x() + other.getLength().x() / 2.0, other.getPosition().y() + other.getLength().y() / 2.0);
559  Position bottomRightCornerOther(other.getPosition().x() - other.getLength().x() / 2.0,
560  other.getPosition().y() - other.getLength().y() / 2.0);
561  // Check if map needs to be resized.
562  bool resizeMap = false;
563  Position extendedMapPosition = position_;
564  Length extendedMapLength = length_;
565  if (topLeftCornerOther.x() > topLeftCorner.x()) {
566  extendedMapPosition.x() += (topLeftCornerOther.x() - topLeftCorner.x()) / 2.0;
567  extendedMapLength.x() += topLeftCornerOther.x() - topLeftCorner.x();
568  resizeMap = true;
569  }
570  if (topLeftCornerOther.y() > topLeftCorner.y()) {
571  extendedMapPosition.y() += (topLeftCornerOther.y() - topLeftCorner.y()) / 2.0;
572  extendedMapLength.y() += topLeftCornerOther.y() - topLeftCorner.y();
573  resizeMap = true;
574  }
575  if (bottomRightCornerOther.x() < bottomRightCorner.x()) {
576  extendedMapPosition.x() -= (bottomRightCorner.x() - bottomRightCornerOther.x()) / 2.0;
577  extendedMapLength.x() += bottomRightCorner.x() - bottomRightCornerOther.x();
578  resizeMap = true;
579  }
580  if (bottomRightCornerOther.y() < bottomRightCorner.y()) {
581  extendedMapPosition.y() -= (bottomRightCorner.y() - bottomRightCornerOther.y()) / 2.0;
582  extendedMapLength.y() += bottomRightCorner.y() - bottomRightCornerOther.y();
583  resizeMap = true;
584  }
585  // Resize map and copy data to new map.
586  if (resizeMap) {
587  GridMap mapCopy = *this;
588  setGeometry(extendedMapLength, resolution_, extendedMapPosition);
589  // Align new map with old one.
590  Vector shift = position_ - mapCopy.getPosition();
591  shift.x() = std::fmod(shift.x(), resolution_);
592  shift.y() = std::fmod(shift.y(), resolution_);
593  if (std::abs(shift.x()) < resolution_ / 2.0) {
594  position_.x() -= shift.x();
595  } else {
596  position_.x() += resolution_ - shift.x();
597  }
598  if (size_.x() % 2 != mapCopy.getSize().x() % 2) {
599  position_.x() += -std::copysign(resolution_ / 2.0, shift.x());
600  }
601  if (std::abs(shift.y()) < resolution_ / 2.0) {
602  position_.y() -= shift.y();
603  } else {
604  position_.y() += resolution_ - shift.y();
605  }
606  if (size_.y() % 2 != mapCopy.getSize().y() % 2) {
607  position_.y() += -std::copysign(resolution_ / 2.0, shift.y());
608  }
609  // Copy data.
610  for (GridMapIterator iterator(*this); !iterator.isPastEnd(); ++iterator) {
611  if (isValid(*iterator)) {
612  continue;
613  }
614  Position position;
615  getPosition(*iterator, position);
616  Index index;
617  if (!mapCopy.isInside(position)) {
618  continue;
619  }
620  mapCopy.getIndex(position, index);
621  for (const auto& layer : layers_) {
622  at(layer, *iterator) = mapCopy.at(layer, index);
623  }
624  }
625  }
626  return true;
627 }
628 
629 void GridMap::setTimestamp(const Time timestamp) {
630  timestamp_ = timestamp;
631 }
632 
634  return timestamp_;
635 }
636 
638  timestamp_ = 0.0;
639 }
640 
641 void GridMap::setFrameId(const std::string& frameId) {
642  frameId_ = frameId;
643 }
644 
645 const std::string& GridMap::getFrameId() const {
646  return frameId_;
647 }
648 
649 const Length& GridMap::getLength() const {
650  return length_;
651 }
652 
654  return position_;
655 }
656 
657 double GridMap::getResolution() const {
658  return resolution_;
659 }
660 
661 const Size& GridMap::getSize() const {
662  return size_;
663 }
664 
665 void GridMap::setStartIndex(const Index& startIndex) {
666  startIndex_ = startIndex;
667 }
668 
670  return startIndex_;
671 }
672 
674  return (startIndex_ == 0).all();
675 }
676 
678  if (isDefaultStartIndex()) {
679  return;
680  }
681 
682  std::vector<BufferRegion> bufferRegions;
683  if (!getBufferRegionsForSubmap(bufferRegions, startIndex_, size_, size_, startIndex_)) {
684  throw std::out_of_range("Cannot access submap of this size.");
685  }
686 
687  for (auto& data : data_) {
688  auto tempData(data.second);
689  for (const auto& bufferRegion : bufferRegions) {
690  Index index = bufferRegion.getStartIndex();
691  Size size = bufferRegion.getSize();
692 
693  if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::TopLeft) {
694  tempData.topLeftCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
695  } else if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::TopRight) {
696  tempData.topRightCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
697  } else if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::BottomLeft) {
698  tempData.bottomLeftCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
699  } else if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::BottomRight) {
700  tempData.bottomRightCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
701  }
702  }
703  data.second = tempData;
704  }
705 
706  startIndex_.setZero();
707 }
708 
710  if (getSize().x() < 1 || getSize().y() < 1) {
711  return position_;
712  }
713 
714  if (isInside(position)) {
715  return position;
716  }
717 
718  Position positionInMap = position;
719 
720  // Find edges.
721  const double halfLengthX = length_.x() * 0.5;
722  const double halfLengthY = length_.y() * 0.5;
723  const Position3 topLeftCorner(position_.x() + halfLengthX, position_.y() + halfLengthY, 0.0);
724  const Position3 topRightCorner(position_.x() + halfLengthX, position_.y() - halfLengthY, 0.0);
725  const Position3 bottomLeftCorner(position_.x() - halfLengthX, position_.y() + halfLengthY, 0.0);
726  const Position3 bottomRightCorner(position_.x() - halfLengthX, position_.y() - halfLengthY, 0.0);
727 
728  // Find constraints.
729  const double maxX = topRightCorner.x();
730  const double minX = bottomRightCorner.x();
731  const double maxY = bottomLeftCorner.y();
732  const double minY = bottomRightCorner.y();
733 
734  // Clip to box constraints and correct for indexing precision.
735  // Points on the border can lead to invalid indices because the cells represent half open intervals, i.e. [...).
736  positionInMap.x() = std::fmin(positionInMap.x(), maxX - std::numeric_limits<double>::epsilon());
737  positionInMap.y() = std::fmin(positionInMap.y(), maxY - std::numeric_limits<double>::epsilon());
738 
739  positionInMap.x() = std::fmax(positionInMap.x(), minX + std::numeric_limits<double>::epsilon());
740  positionInMap.y() = std::fmax(positionInMap.y(), minY + std::numeric_limits<double>::epsilon());
741 
742  return positionInMap;
743 }
744 
745 void GridMap::clear(const std::string& layer) {
746  try {
747  data_.at(layer).setConstant(NAN);
748  } catch (const std::out_of_range& exception) {
749  throw std::out_of_range("GridMap::clear(...) : No map layer '" + layer + "' available.");
750  }
751 }
752 
754  for (auto& layer : basicLayers_) {
755  clear(layer);
756  }
757 }
758 
760  for (auto& data : data_) {
761  data.second.setConstant(NAN);
762  }
763 }
764 
765 void GridMap::clearRows(unsigned int index, unsigned int nRows) {
766  for (auto& layer : layers_) {
767  data_.at(layer).block(index, 0, nRows, getSize()(1)).setConstant(NAN);
768  }
769 }
770 
771 void GridMap::clearCols(unsigned int index, unsigned int nCols) {
772  for (auto& layer : layers_) {
773  data_.at(layer).block(0, index, getSize()(0), nCols).setConstant(NAN);
774  }
775 }
776 
777 bool GridMap::atPositionLinearInterpolated(const std::string& layer, const Position& position, float& value) const {
778  Position point;
779  Index indices[4];
780  bool idxTempDir;
781  size_t idxShift[4];
782 
783  getIndex(position, indices[0]);
784  getPosition(indices[0], point);
785 
786  if (position.x() >= point.x()) {
787  indices[1] = indices[0] + Index(-1, 0); // Second point is above first point.
788  idxTempDir = true;
789  } else {
790  indices[1] = indices[0] + Index(+1, 0);
791  idxTempDir = false;
792  }
793  if (position.y() >= point.y()) {
794  indices[2] = indices[0] + Index(0, -1); // Third point is right of first point.
795  if (idxTempDir) {
796  idxShift[0] = 0;
797  idxShift[1] = 1;
798  idxShift[2] = 2;
799  idxShift[3] = 3;
800  } else {
801  idxShift[0] = 1;
802  idxShift[1] = 0;
803  idxShift[2] = 3;
804  idxShift[3] = 2;
805  }
806 
807  } else {
808  indices[2] = indices[0] + Index(0, +1);
809  if (idxTempDir) {
810  idxShift[0] = 2;
811  idxShift[1] = 3;
812  idxShift[2] = 0;
813  idxShift[3] = 1;
814  } else {
815  idxShift[0] = 3;
816  idxShift[1] = 2;
817  idxShift[2] = 1;
818  idxShift[3] = 0;
819  }
820  }
821  indices[3].x() = indices[1].x();
822  indices[3].y() = indices[2].y();
823 
824  const Size& mapSize = getSize();
825  const size_t bufferSize = mapSize(0) * mapSize(1);
826  const size_t startIndexLin = getLinearIndexFromIndex(startIndex_, mapSize);
827  const size_t endIndexLin = startIndexLin + bufferSize;
828  const auto& layerMat = operator[](layer);
829  float f[4];
830 
831  for (size_t i = 0; i < 4; ++i) {
832  const size_t indexLin = getLinearIndexFromIndex(indices[idxShift[i]], mapSize);
833  if ((indexLin < startIndexLin) || (indexLin > endIndexLin)) {
834  return false;
835  }
836  f[i] = layerMat(indexLin);
837  }
838 
839  getPosition(indices[idxShift[0]], point);
840  const Position positionRed = (position - point) / resolution_;
841  const Position positionRedFlip = Position(1., 1.) - positionRed;
842 
843  value = f[0] * positionRedFlip.x() * positionRedFlip.y() + f[1] * positionRed.x() * positionRedFlip.y() +
844  f[2] * positionRedFlip.x() * positionRed.y() + f[3] * positionRed.x() * positionRed.y();
845  return true;
846 }
847 
848 void GridMap::resize(const Index& size) {
849  size_ = size;
850  for (auto& data : data_) {
851  data.second.resize(size_(0), size_(1));
852  }
853 }
854 
855 
856 bool GridMap::atPositionBicubicConvolutionInterpolated(const std::string& layer, const Position& position,
857  float& value) const
858 {
859  double interpolatedValue = 0.0;
860  if (!bicubic_conv::evaluateBicubicConvolutionInterpolation(*this, layer, position, &interpolatedValue)) {
861  return false;
862  }
863 
864  if (!std::isfinite(interpolatedValue)) {
865  return false;
866  }
867  value = interpolatedValue;
868 
869  return true;
870 }
871 
872 bool GridMap::atPositionBicubicInterpolated(const std::string& layer, const Position& position,
873  float& value) const
874 {
875  double interpolatedValue = 0.0;
876  if (!bicubic::evaluateBicubicInterpolation(*this, layer, position, &interpolatedValue)) {
877  return false;
878  }
879 
880  if (!std::isfinite(interpolatedValue)) {
881  return false;
882  }
883  value = interpolatedValue;
884 
885  return true;
886 
887 }
888 
889 
890 } // namespace grid_map
void setGeometry(const Length &length, const double resolution, const Position &position=Position::Zero())
Definition: GridMap.cpp:44
GridMap getTransformedMap(const Eigen::Isometry3d &transform, const std::string &heightLayerName, const std::string &newFrameId, const double sampleRatio=0.0) const
Definition: GridMap.cpp:332
Size size_
Size of the buffer (rows and cols of the data structure).
Definition: GridMap.hpp:579
bool hasSameLayers(const grid_map::GridMap &other) const
Definition: GridMap.cpp:77
bool isDefaultStartIndex() const
Definition: GridMap.cpp:673
void setPosition(const Position &position)
Definition: GridMap.cpp:438
float & atPosition(const std::string &layer, const Position &position)
Definition: GridMap.cpp:153
void clear(const std::string &layer)
Definition: GridMap.cpp:745
void wrapIndexToRange(Index &index, const Size &bufferSize)
bool getBufferRegionsForSubmap(std::vector< BufferRegion > &submapBufferRegions, const Index &submapIndex, const Size &submapBufferSize, const Size &bufferSize, const Index &bufferStartIndex=Index::Zero())
void setBasicLayers(const std::vector< std::string > &basicLayers)
Definition: GridMap.cpp:65
const Index & getStartIndex() const
Definition: GridMap.cpp:669
double resolution_
Map resolution in xy plane [m/cell].
Definition: GridMap.hpp:573
const Matrix & get(const std::string &layer) const
Definition: GridMap.cpp:104
std::vector< std::string > basicLayers_
Definition: GridMap.hpp:567
const std::vector< std::string > & getBasicLayers() const
Definition: GridMap.cpp:69
std::unordered_map< std::string, Matrix > data_
Grid map data stored as layers of matrices.
Definition: GridMap.hpp:559
const Size & getSize() const
Definition: GridMap.cpp:661
grid_map::DataType DataType
Definition: GridMap.hpp:43
std::string frameId_
Frame id of the grid map.
Definition: GridMap.hpp:553
uint64_t Time
Definition: TypeDefs.hpp:25
const Position & getPosition() const
Definition: GridMap.cpp:653
bool getVector(const std::string &layerPrefix, const Index &index, Eigen::Vector3d &vector) const
Definition: GridMap.cpp:272
const std::vector< std::string > & getLayers() const
Definition: GridMap.cpp:149
bool atPositionBicubicInterpolated(const std::string &layer, const Position &position, float &value) const
Definition: GridMap.cpp:872
bool atPositionLinearInterpolated(const std::string &layer, const Position &position, float &value) const
Definition: GridMap.cpp:777
grid_map::Matrix Matrix
Definition: GridMap.hpp:44
size_t getLinearIndexFromIndex(const Index &index, const Size &bufferSize, bool rowMajor=false)
bool atPositionBicubicConvolutionInterpolated(const std::string &layer, const Position &position, float &value) const
Definition: GridMap.cpp:856
bool move(const Position &position, std::vector< BufferRegion > &newRegions)
Definition: GridMap.cpp:442
void convertToDefaultStartIndex()
Definition: GridMap.cpp:677
double getResolution() const
Definition: GridMap.cpp:657
InterpolationMethods
Definition: TypeDefs.hpp:39
bool isInside(const Position &position) const
Definition: GridMap.cpp:236
bool hasBasicLayers() const
Definition: GridMap.cpp:73
bool getIndexFromPosition(Index &index, const Position &position, const Length &mapLength, const Position &mapPosition, const double &resolution, const Size &bufferSize, const Index &bufferStartIndex=Index::Zero())
bool addDataFrom(const GridMap &other, bool extendMap, bool overwriteData, bool copyAllLayers, std::vector< std::string > layers=std::vector< std::string >())
Definition: GridMap.cpp:514
bool extendToInclude(const GridMap &other)
Definition: GridMap.cpp:554
bool checkIfPositionWithinMap(const Position &position, const Length &mapLength, const Position &mapPosition)
bool getPositionShiftFromIndexShift(Vector &positionShift, const Index &indexShift, const double &resolution)
std::vector< std::string > layers_
Names of the data layers.
Definition: GridMap.hpp:562
Eigen::Vector2d Position
Definition: TypeDefs.hpp:18
bool isValid(const Index &index) const
Definition: GridMap.cpp:244
void resetTimestamp()
Definition: GridMap.cpp:637
Eigen::Array2i Index
Definition: TypeDefs.hpp:22
void setStartIndex(const Index &startIndex)
Definition: GridMap.cpp:665
Eigen::Array2i Size
Definition: TypeDefs.hpp:23
GridMap getSubmap(const Position &position, const Length &length, bool &isSuccess) const
Definition: GridMap.cpp:282
double getResolution() const
const Position & getPosition() const
Position position_
Map position in the grid map frame [m].
Definition: GridMap.hpp:576
const Index & getStartIndex() const
Eigen::Array2d Length
Definition: TypeDefs.hpp:24
Position getClosestPositionInMap(const Position &position) const
Definition: GridMap.cpp:709
float & at(const std::string &layer, const Index &index)
Definition: GridMap.cpp:212
Time timestamp_
Timestamp of the grid map (nanoseconds).
Definition: GridMap.hpp:556
const std::string & getFrameId() const
Definition: GridMap.cpp:645
Index startIndex_
Circular buffer start indices.
Definition: GridMap.hpp:582
void add(const std::string &layer, const double value=NAN)
Definition: GridMap.cpp:82
Time getTimestamp() const
Definition: GridMap.cpp:633
Eigen::Vector3d Position3
Definition: TypeDefs.hpp:20
bool exists(const std::string &layer) const
Definition: GridMap.cpp:100
bool evaluateBicubicConvolutionInterpolation(const GridMap &gridMap, const std::string &layer, const Position &queriedPosition, double *interpolatedValue)
bool getPositionFromIndex(Position &position, const Index &index, const Length &mapLength, const Position &mapPosition, const double &resolution, const Size &bufferSize, const Index &bufferStartIndex=Index::Zero())
const Length & getLength() const
bool getPosition3(const std::string &layer, const Index &index, Position3 &position) const
Definition: GridMap.cpp:260
void clearCols(unsigned int index, unsigned int nCols)
Definition: GridMap.cpp:771
void clearRows(unsigned int index, unsigned int nRows)
Definition: GridMap.cpp:765
Length length_
Side length of the map in x- and y-direction [m].
Definition: GridMap.hpp:570
bool getIndexShiftFromPositionShift(Index &indexShift, const Vector &positionShift, const double &resolution)
void setFrameId(const std::string &frameId)
Definition: GridMap.cpp:641
bool getIndex(const Position &position, Index &index) const
Definition: GridMap.cpp:228
void setTimestamp(const Time timestamp)
Definition: GridMap.cpp:629
bool erase(const std::string &layer)
Definition: GridMap.cpp:128
bool getPosition(const Index &index, Position &position) const
Definition: GridMap.cpp:232
bool evaluateBicubicInterpolation(const GridMap &gridMap, const std::string &layer, const Position &queriedPosition, double *interpolatedValue)
const Matrix & operator[](const std::string &layer) const
Definition: GridMap.cpp:120
void resize(const Index &bufferSize)
Definition: GridMap.cpp:848
Eigen::Vector2d Vector
Definition: TypeDefs.hpp:19
const Length & getLength() const
Definition: GridMap.cpp:649


grid_map_core
Author(s): Péter Fankhauser
autogenerated on Wed Jul 5 2023 02:23:35