14 #include <Eigen/Dense> 27 GridMap::GridMap(
const std::vector<std::string>& layers)
33 startIndex_.setZero();
37 for (
auto& layer : layers_) {
38 data_.insert(std::pair<std::string, Matrix>(layer,
Matrix()));
54 assert(length(0) > 0.0);
55 assert(length(1) > 0.0);
56 assert(resolution > 0.0);
59 size(0) =
static_cast<int>(round(length(0) / resolution));
60 size(1) =
static_cast<int>(round(length(1) / resolution));
94 for (
const auto& layer :
layers_) {
95 if (!other.
exists(layer))
return false;
107 assert(
size_(0) == data.rows());
108 assert(
size_(1) == data.cols());
112 data_.at(layer) = data;
115 data_.insert(std::pair<std::string, Matrix>(layer, data));
128 return data_.at(layer);
129 }
catch (
const std::out_of_range& exception) {
130 throw std::out_of_range(
"GridMap::get(...) : No map layer '" + layer +
"' available.");
137 return data_.at(layer);
138 }
catch (
const std::out_of_range& exception) {
139 throw std::out_of_range(
"GridMap::get(...) : No map layer of type '" + layer +
"' available.");
155 const auto dataIterator =
data_.find(layer);
156 if (dataIterator ==
data_.end())
return false;
157 data_.erase(dataIterator);
159 const auto layerIterator = std::find(
layers_.begin(),
layers_.end(), layer);
160 if (layerIterator ==
layers_.end())
return false;
178 return at(layer, index);
180 throw std::out_of_range(
"GridMap::atPosition(...) : Position is out of range.");
185 switch (interpolationMethod) {
198 return at(layer, index);
201 throw std::out_of_range(
"GridMap::atPosition(...) : Position is out of range.");
205 throw std::runtime_error(
"GridMap::atPosition(...) : Specified interpolation method not implemented.");
212 return data_.at(layer)(index(0), index(1));
213 }
catch (
const std::out_of_range& exception) {
214 throw std::out_of_range(
"GridMap::at(...) : No map layer '" + layer +
"' available.");
221 return data_.at(layer)(index(0), index(1));
222 }
catch (
const std::out_of_range& exception) {
223 throw std::out_of_range(
"GridMap::at(...) : No map layer '" + layer +
"' available.");
249 if (!isfinite(
at(layer, index)))
return false;
255 if (layers.empty())
return false;
256 for (
auto& layer : layers) {
257 if (!isfinite(
at(layer, index)))
return false;
265 if (!
isValid(index, layer))
return false;
268 position.head(2) = position2d;
269 position.z() =
at(layer, index);
274 Eigen::Vector3d& vector)
const 276 std::vector<std::string> layers;
277 layers.push_back(layerPrefix +
"x");
278 layers.push_back(layerPrefix +
"y");
279 layers.push_back(layerPrefix +
"z");
280 if (!
isValid(index, layers))
return false;
281 for (
size_t i = 0; i < 3; ++i) {
282 vector(i) =
at(layers[i], index);
288 bool& isSuccess)
const 291 return getSubmap(position, length, index, isSuccess);
295 Index& indexInSubmap,
bool& isSuccess)
const 304 SubmapGeometry submapInformation(*
this, position, length, isSuccess);
310 std::vector<BufferRegion> bufferRegions;
314 cout <<
"Cannot access submap of this size." << endl;
319 for (
const auto& data :
data_) {
320 for (
const auto& bufferRegion : bufferRegions) {
321 Index index = bufferRegion.getStartIndex();
322 Size size = bufferRegion.getSize();
325 submap.
data_[data.first].topLeftCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
327 submap.
data_[data.first].topRightCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
329 submap.
data_[data.first].bottomLeftCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
331 submap.
data_[data.first].bottomRightCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
342 const std::string& newFrameId,
343 const double sampleRatio)
const 346 if (!
exists(heightLayerName)) {
347 throw std::out_of_range(
"GridMap::getTransformedMap(...) : No map layer '" + heightLayerName +
"' available.");
351 std::vector<Position3> positionSamples;
355 const double sampleLength =
resolution_*sampleRatio;
358 const double halfLengthX =
length_.x()*0.5;
359 const double halfLengthY =
length_.y()*0.5;
365 std::vector<Position3> newEdges;
367 newEdges.push_back(transform * topLeftCorner);
368 newEdges.push_back(transform * topRightCorner);
369 newEdges.push_back(transform * bottomLeftCorner);
370 newEdges.push_back(transform * bottomRightCorner);
375 for (
const auto& newEdge : newEdges) { newCenter += newEdge; }
380 for (
const auto& newEdge : newEdges) {
381 Position3 positionCenterToEdge = newEdge-newCenter;
382 maxLengthFromCenter.x() = std::fmax(std::fabs(positionCenterToEdge.x()), maxLengthFromCenter.x());
383 maxLengthFromCenter.y() = std::fmax(std::fabs(positionCenterToEdge.y()), maxLengthFromCenter.y());
385 Length newLength = 2.0*maxLengthFromCenter;
397 if(!
getPosition3(heightLayerName, *iterator, center)) {
continue; }
400 positionSamples.clear();
402 if (sampleRatio>0.0) {
403 positionSamples.reserve(5);
404 positionSamples.push_back(center);
405 positionSamples.push_back(
Position3(center.x() - sampleLength,
408 positionSamples.push_back(
Position3(center.x() + sampleLength,
411 positionSamples.push_back(
Position3(center.x(),
412 center.y() - sampleLength,
414 positionSamples.push_back(
Position3(center.x(),
415 center.y() + sampleLength,
418 positionSamples.push_back(center);
423 for (
const auto& position : positionSamples){
424 const Position3 transformedPosition = transform * position;
427 if(!newMap.
getIndex(
Position(transformedPosition.x(), transformedPosition.y()), newIndex)) {
continue; }
430 const auto newExistingValue = newMap.
at(heightLayerName, newIndex);
431 if(!std::isnan(newExistingValue) && newExistingValue > transformedPosition.z()){
436 for(
const auto& layer:
layers_){
437 const auto currentValueInOldGrid =
at(layer, *iterator);
438 auto& newValue = newMap.
at(layer, newIndex);
439 if(layer == heightLayerName) { newValue = transformedPosition.z(); }
440 else { newValue = currentValueInOldGrid; }
462 for (
int i = 0; i < indexShift.size(); i++) {
463 if (indexShift(i) != 0) {
464 if (abs(indexShift(i)) >=
getSize()(i)) {
470 int sign = (indexShift(i) > 0 ? 1 : -1);
471 int startIndex =
startIndex_(i) - (sign < 0 ? 1 : 0);
472 int endIndex = startIndex - sign + indexShift(i);
473 int nCells = abs(indexShift(i));
474 int index = (sign > 0 ? startIndex : endIndex);
477 if (index + nCells <=
getSize()(i)) {
488 int firstIndex = index;
489 int firstNCells =
getSize()(i) - firstIndex;
499 int secondNCells = nCells - firstNCells;
515 position_ += alignedPositionShift;
518 return (indexShift.any() != 0);
523 std::vector<BufferRegion> newRegions;
524 return move(position, newRegions);
528 bool copyAllLayers, std::vector<std::string> layers)
531 if (copyAllLayers) layers = other.
getLayers();
537 for (
const auto& layer : layers) {
544 if (
isValid(*iterator) && !overwriteData)
continue;
548 if (!other.
isInside(position))
continue;
550 for (
const auto& layer : layers) {
551 if (!other.
isValid(index, layer))
continue;
552 at(layer, *iterator) = other.
at(layer, index);
567 bool resizeMap =
false;
570 if (topLeftCornerOther.x() > topLeftCorner.x()) {
571 extendedMapPosition.x() += (topLeftCornerOther.x() - topLeftCorner.x()) / 2.0;
572 extendedMapLength.x() += topLeftCornerOther.x() - topLeftCorner.x();
575 if (topLeftCornerOther.y() > topLeftCorner.y()) {
576 extendedMapPosition.y() += (topLeftCornerOther.y() - topLeftCorner.y()) / 2.0;
577 extendedMapLength.y() += topLeftCornerOther.y() - topLeftCorner.y();
580 if (bottomRightCornerOther.x() < bottomRightCorner.x()) {
581 extendedMapPosition.x() -= (bottomRightCorner.x() - bottomRightCornerOther.x()) / 2.0;
582 extendedMapLength.x() += bottomRightCorner.x() - bottomRightCornerOther.x();
585 if (bottomRightCornerOther.y() < bottomRightCorner.y()) {
586 extendedMapPosition.y() -= (bottomRightCorner.y() - bottomRightCornerOther.y()) / 2.0;
587 extendedMapLength.y() += bottomRightCorner.y() - bottomRightCornerOther.y();
616 if (
isValid(*iterator))
continue;
620 if (!mapCopy.
isInside(position))
continue;
622 for (
const auto& layer :
layers_) {
623 at(layer, *iterator) = mapCopy.
at(layer, index);
693 std::vector<BufferRegion> bufferRegions;
695 throw std::out_of_range(
"Cannot access submap of this size.");
698 for (
auto& data :
data_) {
699 auto tempData(data.second);
700 for (
const auto& bufferRegion : bufferRegions) {
701 Index index = bufferRegion.getStartIndex();
702 Size size = bufferRegion.getSize();
705 tempData.topLeftCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
707 tempData.topRightCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
709 tempData.bottomLeftCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
711 tempData.bottomRightCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
714 data.second = tempData;
723 data_.at(layer).setConstant(NAN);
724 }
catch (
const std::out_of_range& exception) {
725 throw std::out_of_range(
"GridMap::clear(...) : No map layer '" + layer +
"' available.");
738 for (
auto& data :
data_) {
739 data.second.setConstant(NAN);
745 std::vector<std::string> layersToClear;
748 for (
auto& layer : layersToClear) {
749 data_.at(layer).block(index, 0, nRows,
getSize()(1)).setConstant(NAN);
755 std::vector<std::string> layersToClear;
758 for (
auto& layer : layersToClear) {
759 data_.at(layer).block(0, index,
getSize()(0), nCols).setConstant(NAN);
774 if (position.x() >= point.x()) {
775 indices[1] = indices[0] +
Index(-1, 0);
778 indices[1] = indices[0] +
Index(+1, 0);
781 if (position.y() >= point.y()) {
782 indices[2] = indices[0] +
Index(0, -1);
783 if(idxTempDir){ idxShift[0]=0; idxShift[1]=1; idxShift[2]=2; idxShift[3]=3; }
784 else { idxShift[0]=1; idxShift[1]=0; idxShift[2]=3; idxShift[3]=2; }
788 indices[2] = indices[0] +
Index(0, +1);
789 if(idxTempDir){ idxShift[0]=2; idxShift[1]=3; idxShift[2]=0; idxShift[3]=1; }
790 else { idxShift[0]=3; idxShift[1]=2; idxShift[2]=1; idxShift[3]=0; }
792 indices[3].x() = indices[1].x();
793 indices[3].y() = indices[2].y();
796 const size_t bufferSize = mapSize(0) * mapSize(1);
798 const size_t endIndexLin = startIndexLin + bufferSize;
802 for (
size_t i = 0; i < 4; ++i) {
804 if ((indexLin < startIndexLin) || (indexLin > endIndexLin))
return false;
805 f[i] = layerMat(indexLin);
812 value = f[0] * positionRedFlip.x() * positionRedFlip.y() +
813 f[1] * positionRed.x() * positionRedFlip.y() +
814 f[2] * positionRedFlip.x() * positionRed.y() +
815 f[3] * positionRed.x() * positionRed.y();
822 for (
auto& data :
data_) {
const Length & getLength() const
double getResolution() const
void setGeometry(const Length &length, const double resolution, const Position &position=Position::Zero())
Time getTimestamp() const
Size size_
Size of the buffer (rows and cols of the data structure).
void setPosition(const Position &position)
float & atPosition(const std::string &layer, const Position &position)
const Index & getStartIndex() const
void clear(const std::string &layer)
bool getPosition(const Index &index, Position &position) const
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)
const Position & getPosition() const
const std::string & getFrameId() const
double resolution_
Map resolution in xy plane [m/cell].
GridMap getTransformedMap(const Eigen::Isometry3d &transform, const std::string &heightLayerName, const std::string &newFrameId, const double sampleRatio=0.0) const
std::vector< std::string > basicLayers_
std::unordered_map< std::string, Matrix > data_
Grid map data stored as layers of matrices.
bool getVector(const std::string &layerPrefix, const Index &index, Eigen::Vector3d &vector) const
std::string frameId_
Frame id of the grid map.
const Matrix & operator[](const std::string &layer) const
bool move(const Position &position, std::vector< BufferRegion > &newRegions)
void convertToDefaultStartIndex()
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 >())
GridMap getSubmap(const Position &position, const Length &length, bool &isSuccess) const
bool isValid(const Index &index) const
const Length & getLength() const
Eigen::Vector3d Position3
bool exists(const std::string &layer) const
bool extendToInclude(const GridMap &other)
bool checkIfPositionWithinMap(const Position &position, const Length &mapLength, const Position &mapPosition)
double getResolution() const
const std::vector< std::string > & getLayers() const
bool getPositionShiftFromIndexShift(Vector &positionShift, const Index &indexShift, const double &resolution)
std::vector< std::string > layers_
Names of the data layers.
bool isInside(const Position &position) const
bool isDefaultStartIndex() const
const Matrix & get(const std::string &layer) const
const Position & getPosition() const
void setStartIndex(const Index &startIndex)
Position position_
Map position in the grid map frame [m].
float & at(const std::string &layer, const Index &index)
bool hasSameLayers(const grid_map::GridMap &other) const
Time timestamp_
Timestamp of the grid map (nanoseconds).
bool hasBasicLayers() const
Index startIndex_
Circular buffer start indeces.
void add(const std::string &layer, const double value=NAN)
size_t getLinearIndexFromIndex(const Index &index, const Size &bufferSize, const bool rowMajor=false)
bool atPositionLinearInterpolated(const std::string &layer, const Position &position, float &value) const
bool getPositionFromIndex(Position &position, const Index &index, const Length &mapLength, const Position &mapPosition, const double &resolution, const Size &bufferSize, const Index &bufferStartIndex=Index::Zero())
void clearCols(unsigned int index, unsigned int nCols)
void clearRows(unsigned int index, unsigned int nRows)
Length length_
Side length of the map in x- and y-direction [m].
bool getIndexShiftFromPositionShift(Index &indexShift, const Vector &positionShift, const double &resolution)
void setFrameId(const std::string &frameId)
const Index & getStartIndex() const
void setTimestamp(const Time timestamp)
bool erase(const std::string &layer)
bool getIndex(const Position &position, Index &index) const
bool getPosition3(const std::string &layer, const Index &index, Position3 &position) const
void resize(const Index &bufferSize)
const std::vector< std::string > & getBasicLayers() const
const Size & getSize() const