00001
00002
00003
00004
00005
00006
00007
00008
00009 #include "grid_map_core/GridMap.hpp"
00010 #include "grid_map_core/GridMapMath.hpp"
00011 #include "grid_map_core/SubmapGeometry.hpp"
00012 #include "grid_map_core/iterators/GridMapIterator.hpp"
00013
00014 #include <Eigen/Dense>
00015
00016 #include <iostream>
00017 #include <cassert>
00018 #include <math.h>
00019 #include <algorithm>
00020 #include <stdexcept>
00021
00022 using namespace std;
00023 using namespace grid_map;
00024
00025 namespace grid_map {
00026
00027 GridMap::GridMap(const std::vector<std::string>& layers)
00028 {
00029 position_.setZero();
00030 length_.setZero();
00031 resolution_ = 0.0;
00032 size_.setZero();
00033 startIndex_.setZero();
00034 timestamp_ = 0;
00035 layers_ = layers;
00036
00037 for (auto& layer : layers_) {
00038 data_.insert(std::pair<std::string, Matrix>(layer, Matrix()));
00039 }
00040 }
00041
00042 GridMap::GridMap() :
00043 GridMap(std::vector<std::string>())
00044 {
00045 }
00046
00047 GridMap::~GridMap()
00048 {
00049 }
00050
00051 void GridMap::setGeometry(const Length& length, const double resolution,
00052 const Position& position)
00053 {
00054 assert(length(0) > 0.0);
00055 assert(length(1) > 0.0);
00056 assert(resolution > 0.0);
00057
00058 Size size;
00059 size(0) = static_cast<int>(round(length(0) / resolution));
00060 size(1) = static_cast<int>(round(length(1) / resolution));
00061 resize(size);
00062 clearAll();
00063
00064 resolution_ = resolution;
00065 length_ = (size_.cast<double>() * resolution_).matrix();
00066 position_ = position;
00067 startIndex_.setZero();
00068
00069 return;
00070 }
00071
00072 void GridMap::setGeometry(const SubmapGeometry& geometry)
00073 {
00074 setGeometry(geometry.getLength(), geometry.getResolution(), geometry.getPosition());
00075 }
00076
00077 void GridMap::setBasicLayers(const std::vector<std::string>& basicLayers)
00078 {
00079 basicLayers_ = basicLayers;
00080 }
00081
00082 const std::vector<std::string>& GridMap::getBasicLayers() const
00083 {
00084 return basicLayers_;
00085 }
00086
00087 bool GridMap::hasBasicLayers() const
00088 {
00089 return basicLayers_.size() > 0;
00090 }
00091
00092 bool GridMap::hasSameLayers(const GridMap& other) const
00093 {
00094 for (const auto& layer : layers_) {
00095 if (!other.exists(layer)) return false;
00096 }
00097 return true;
00098 }
00099
00100 void GridMap::add(const std::string& layer, const double value)
00101 {
00102 add(layer, Matrix::Constant(size_(0), size_(1), value));
00103 }
00104
00105 void GridMap::add(const std::string& layer, const Matrix& data)
00106 {
00107 assert(size_(0) == data.rows());
00108 assert(size_(1) == data.cols());
00109
00110 if (exists(layer)) {
00111
00112 data_.at(layer) = data;
00113 } else {
00114
00115 data_.insert(std::pair<std::string, Matrix>(layer, data));
00116 layers_.push_back(layer);
00117 }
00118 }
00119
00120 bool GridMap::exists(const std::string& layer) const
00121 {
00122 return !(data_.find(layer) == data_.end());
00123 }
00124
00125 const Matrix& GridMap::get(const std::string& layer) const
00126 {
00127 try {
00128 return data_.at(layer);
00129 } catch (const std::out_of_range& exception) {
00130 throw std::out_of_range("GridMap::get(...) : No map layer '" + layer + "' available.");
00131 }
00132 }
00133
00134 Matrix& GridMap::get(const std::string& layer)
00135 {
00136 try {
00137 return data_.at(layer);
00138 } catch (const std::out_of_range& exception) {
00139 throw std::out_of_range("GridMap::get(...) : No map layer of type '" + layer + "' available.");
00140 }
00141 }
00142
00143 const Matrix& GridMap::operator [](const std::string& layer) const
00144 {
00145 return get(layer);
00146 }
00147
00148 Matrix& GridMap::operator [](const std::string& layer)
00149 {
00150 return get(layer);
00151 }
00152
00153 bool GridMap::erase(const std::string& layer)
00154 {
00155 const auto dataIterator = data_.find(layer);
00156 if (dataIterator == data_.end()) return false;
00157 data_.erase(dataIterator);
00158
00159 const auto layerIterator = std::find(layers_.begin(), layers_.end(), layer);
00160 if (layerIterator == layers_.end()) return false;
00161 layers_.erase(layerIterator);
00162
00163 const auto basicLayerIterator = std::find(basicLayers_.begin(), basicLayers_.end(), layer);
00164 if (basicLayerIterator != basicLayers_.end()) basicLayers_.erase(basicLayerIterator);
00165
00166 return true;
00167 }
00168
00169 const std::vector<std::string>& GridMap::getLayers() const
00170 {
00171 return layers_;
00172 }
00173
00174 float& GridMap::atPosition(const std::string& layer, const Position& position)
00175 {
00176 Index index;
00177 if (getIndex(position, index)) {
00178 return at(layer, index);
00179 }
00180 throw std::out_of_range("GridMap::atPosition(...) : Position is out of range.");
00181 }
00182
00183 float GridMap::atPosition(const std::string& layer, const Position& position, InterpolationMethods interpolationMethod) const
00184 {
00185 switch (interpolationMethod) {
00186 case InterpolationMethods::INTER_LINEAR:
00187 {
00188 float value;
00189 if (atPositionLinearInterpolated(layer, position, value))
00190 return value;
00191 else
00192 interpolationMethod = InterpolationMethods::INTER_NEAREST;
00193 }
00194 case InterpolationMethods::INTER_NEAREST:
00195 {
00196 Index index;
00197 if (getIndex(position, index)) {
00198 return at(layer, index);
00199 }
00200 else
00201 throw std::out_of_range("GridMap::atPosition(...) : Position is out of range.");
00202 break;
00203 }
00204 default:
00205 throw std::runtime_error("GridMap::atPosition(...) : Specified interpolation method not implemented.");
00206 }
00207 }
00208
00209 float& GridMap::at(const std::string& layer, const Index& index)
00210 {
00211 try {
00212 return data_.at(layer)(index(0), index(1));
00213 } catch (const std::out_of_range& exception) {
00214 throw std::out_of_range("GridMap::at(...) : No map layer '" + layer + "' available.");
00215 }
00216 }
00217
00218 float GridMap::at(const std::string& layer, const Index& index) const
00219 {
00220 try {
00221 return data_.at(layer)(index(0), index(1));
00222 } catch (const std::out_of_range& exception) {
00223 throw std::out_of_range("GridMap::at(...) : No map layer '" + layer + "' available.");
00224 }
00225 }
00226
00227 bool GridMap::getIndex(const Position& position, Index& index) const
00228 {
00229 return getIndexFromPosition(index, position, length_, position_, resolution_, size_, startIndex_);
00230 }
00231
00232 bool GridMap::getPosition(const Index& index, Position& position) const
00233 {
00234 return getPositionFromIndex(position, index, length_, position_, resolution_, size_, startIndex_);
00235 }
00236
00237 bool GridMap::isInside(const Position& position) const
00238 {
00239 return checkIfPositionWithinMap(position, length_, position_);
00240 }
00241
00242 bool GridMap::isValid(const Index& index) const
00243 {
00244 return isValid(index, basicLayers_);
00245 }
00246
00247 bool GridMap::isValid(const Index& index, const std::string& layer) const
00248 {
00249 if (!isfinite(at(layer, index))) return false;
00250 return true;
00251 }
00252
00253 bool GridMap::isValid(const Index& index, const std::vector<std::string>& layers) const
00254 {
00255 if (layers.empty()) return false;
00256 for (auto& layer : layers) {
00257 if (!isfinite(at(layer, index))) return false;
00258 }
00259 return true;
00260 }
00261
00262 bool GridMap::getPosition3(const std::string& layer, const Index& index,
00263 Position3& position) const
00264 {
00265 if (!isValid(index, layer)) return false;
00266 Position position2d;
00267 getPosition(index, position2d);
00268 position.head(2) = position2d;
00269 position.z() = at(layer, index);
00270 return true;
00271 }
00272
00273 bool GridMap::getVector(const std::string& layerPrefix, const Index& index,
00274 Eigen::Vector3d& vector) const
00275 {
00276 std::vector<std::string> layers;
00277 layers.push_back(layerPrefix + "x");
00278 layers.push_back(layerPrefix + "y");
00279 layers.push_back(layerPrefix + "z");
00280 if (!isValid(index, layers)) return false;
00281 for (size_t i = 0; i < 3; ++i) {
00282 vector(i) = at(layers[i], index);
00283 }
00284 return true;
00285 }
00286
00287 GridMap GridMap::getSubmap(const Position& position, const Length& length,
00288 bool& isSuccess) const
00289 {
00290 Index index;
00291 return getSubmap(position, length, index, isSuccess);
00292 }
00293
00294 GridMap GridMap::getSubmap(const Position& position, const Length& length,
00295 Index& indexInSubmap, bool& isSuccess) const
00296 {
00297
00298 GridMap submap(layers_);
00299 submap.setBasicLayers(basicLayers_);
00300 submap.setTimestamp(timestamp_);
00301 submap.setFrameId(frameId_);
00302
00303
00304 SubmapGeometry submapInformation(*this, position, length, isSuccess);
00305 if (isSuccess == false) return GridMap(layers_);
00306 submap.setGeometry(submapInformation);
00307 submap.startIndex_.setZero();
00308
00309
00310 std::vector<BufferRegion> bufferRegions;
00311
00312 if (!getBufferRegionsForSubmap(bufferRegions, submapInformation.getStartIndex(),
00313 submap.getSize(), size_, startIndex_)) {
00314 cout << "Cannot access submap of this size." << endl;
00315 isSuccess = false;
00316 return GridMap(layers_);
00317 }
00318
00319 for (const auto& data : data_) {
00320 for (const auto& bufferRegion : bufferRegions) {
00321 Index index = bufferRegion.getStartIndex();
00322 Size size = bufferRegion.getSize();
00323
00324 if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::TopLeft) {
00325 submap.data_[data.first].topLeftCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
00326 } else if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::TopRight) {
00327 submap.data_[data.first].topRightCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
00328 } else if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::BottomLeft) {
00329 submap.data_[data.first].bottomLeftCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
00330 } else if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::BottomRight) {
00331 submap.data_[data.first].bottomRightCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
00332 }
00333
00334 }
00335 }
00336
00337 isSuccess = true;
00338 return submap;
00339 }
00340
00341 GridMap GridMap::getTransformedMap(const Eigen::Isometry3d& transform, const std::string& heightLayerName,
00342 const std::string& newFrameId,
00343 const double sampleRatio) const
00344 {
00345
00346 if (!exists(heightLayerName)) {
00347 throw std::out_of_range("GridMap::getTransformedMap(...) : No map layer '" + heightLayerName + "' available.");
00348 }
00349
00350
00351 std::vector<Position3> positionSamples;
00352 Position3 center;
00353 Index newIndex;
00354
00355 const double sampleLength = resolution_*sampleRatio;
00356
00357
00358 const double halfLengthX = length_.x()*0.5;
00359 const double halfLengthY = length_.y()*0.5;
00360 const Position3 topLeftCorner (position_.x() + halfLengthX, position_.y() + halfLengthY, 0.0);
00361 const Position3 topRightCorner (position_.x() + halfLengthX, position_.y() - halfLengthY, 0.0);
00362 const Position3 bottomLeftCorner (position_.x() - halfLengthX, position_.y() + halfLengthY, 0.0);
00363 const Position3 bottomRightCorner (position_.x() - halfLengthX, position_.y() - halfLengthY, 0.0);
00364
00365 std::vector<Position3> newEdges;
00366 newEdges.reserve(4);
00367 newEdges.push_back(transform * topLeftCorner);
00368 newEdges.push_back(transform * topRightCorner);
00369 newEdges.push_back(transform * bottomLeftCorner);
00370 newEdges.push_back(transform * bottomRightCorner);
00371
00372
00373
00374 Position3 newCenter = Position3::Zero();
00375 for (const auto& newEdge : newEdges) { newCenter += newEdge; }
00376 newCenter *= 0.25;
00377
00378
00379 Length maxLengthFromCenter = Length(0.0, 0.0);
00380 for (const auto& newEdge : newEdges) {
00381 Position3 positionCenterToEdge = newEdge-newCenter;
00382 maxLengthFromCenter.x() = std::fmax(std::fabs(positionCenterToEdge.x()), maxLengthFromCenter.x());
00383 maxLengthFromCenter.y() = std::fmax(std::fabs(positionCenterToEdge.y()), maxLengthFromCenter.y());
00384 }
00385 Length newLength = 2.0*maxLengthFromCenter;
00386
00387
00388 GridMap newMap(layers_);
00389 newMap.setBasicLayers(basicLayers_);
00390 newMap.setTimestamp(timestamp_);
00391 newMap.setFrameId(newFrameId);
00392 newMap.setGeometry(newLength, resolution_, Position(newCenter.x(), newCenter.y()));
00393 newMap.startIndex_.setZero();
00394
00395 for (GridMapIterator iterator(*this); !iterator.isPastEnd(); ++iterator) {
00396
00397 if(!getPosition3(heightLayerName, *iterator, center)) { continue; }
00398
00399
00400 positionSamples.clear();
00401
00402 if (sampleRatio>0.0) {
00403 positionSamples.reserve(5);
00404 positionSamples.push_back(center);
00405 positionSamples.push_back(Position3(center.x() - sampleLength,
00406 center.y(),
00407 center.z()));
00408 positionSamples.push_back(Position3(center.x() + sampleLength,
00409 center.y(),
00410 center.z()));
00411 positionSamples.push_back(Position3(center.x(),
00412 center.y() - sampleLength,
00413 center.z()));
00414 positionSamples.push_back(Position3(center.x(),
00415 center.y() + sampleLength,
00416 center.z()));
00417 } else {
00418 positionSamples.push_back(center);
00419 }
00420
00421
00422
00423 for (const auto& position : positionSamples){
00424 const Position3 transformedPosition = transform * position;
00425
00426
00427 if(!newMap.getIndex(Position(transformedPosition.x(), transformedPosition.y()), newIndex)) { continue; }
00428
00429
00430 const auto newExistingValue = newMap.at(heightLayerName, newIndex);
00431 if(!std::isnan(newExistingValue) && newExistingValue > transformedPosition.z()){
00432 continue;
00433 }
00434
00435
00436 for(const auto& layer: layers_){
00437 const auto currentValueInOldGrid = at(layer, *iterator);
00438 auto& newValue = newMap.at(layer, newIndex);
00439 if(layer == heightLayerName) { newValue = transformedPosition.z(); }
00440 else { newValue = currentValueInOldGrid; }
00441 }
00442 }
00443 }
00444
00445 return newMap;
00446 }
00447
00448 void GridMap::setPosition(const Position& position)
00449 {
00450 position_ = position;
00451 }
00452
00453 bool GridMap::move(const Position& position, std::vector<BufferRegion>& newRegions)
00454 {
00455 Index indexShift;
00456 Position positionShift = position - position_;
00457 getIndexShiftFromPositionShift(indexShift, positionShift, resolution_);
00458 Position alignedPositionShift;
00459 getPositionShiftFromIndexShift(alignedPositionShift, indexShift, resolution_);
00460
00461
00462 for (int i = 0; i < indexShift.size(); i++) {
00463 if (indexShift(i) != 0) {
00464 if (abs(indexShift(i)) >= getSize()(i)) {
00465
00466 clearAll();
00467 newRegions.push_back(BufferRegion(Index(0, 0), getSize(), BufferRegion::Quadrant::Undefined));
00468 } else {
00469
00470 int sign = (indexShift(i) > 0 ? 1 : -1);
00471 int startIndex = startIndex_(i) - (sign < 0 ? 1 : 0);
00472 int endIndex = startIndex - sign + indexShift(i);
00473 int nCells = abs(indexShift(i));
00474 int index = (sign > 0 ? startIndex : endIndex);
00475 wrapIndexToRange(index, getSize()(i));
00476
00477 if (index + nCells <= getSize()(i)) {
00478
00479 if (i == 0) {
00480 clearRows(index, nCells);
00481 newRegions.push_back(BufferRegion(Index(index, 0), Size(nCells, getSize()(1)), BufferRegion::Quadrant::Undefined));
00482 } else if (i == 1) {
00483 clearCols(index, nCells);
00484 newRegions.push_back(BufferRegion(Index(0, index), Size(getSize()(0), nCells), BufferRegion::Quadrant::Undefined));
00485 }
00486 } else {
00487
00488 int firstIndex = index;
00489 int firstNCells = getSize()(i) - firstIndex;
00490 if (i == 0) {
00491 clearRows(firstIndex, firstNCells);
00492 newRegions.push_back(BufferRegion(Index(firstIndex, 0), Size(firstNCells, getSize()(1)), BufferRegion::Quadrant::Undefined));
00493 } else if (i == 1) {
00494 clearCols(firstIndex, firstNCells);
00495 newRegions.push_back(BufferRegion(Index(0, firstIndex), Size(getSize()(0), firstNCells), BufferRegion::Quadrant::Undefined));
00496 }
00497
00498 int secondIndex = 0;
00499 int secondNCells = nCells - firstNCells;
00500 if (i == 0) {
00501 clearRows(secondIndex, secondNCells);
00502 newRegions.push_back(BufferRegion(Index(secondIndex, 0), Size(secondNCells, getSize()(1)), BufferRegion::Quadrant::Undefined));
00503 } else if (i == 1) {
00504 clearCols(secondIndex, secondNCells);
00505 newRegions.push_back(BufferRegion(Index(0, secondIndex), Size(getSize()(0), secondNCells), BufferRegion::Quadrant::Undefined));
00506 }
00507 }
00508 }
00509 }
00510 }
00511
00512
00513 startIndex_ += indexShift;
00514 wrapIndexToRange(startIndex_, getSize());
00515 position_ += alignedPositionShift;
00516
00517
00518 return (indexShift.any() != 0);
00519 }
00520
00521 bool GridMap::move(const Position& position)
00522 {
00523 std::vector<BufferRegion> newRegions;
00524 return move(position, newRegions);
00525 }
00526
00527 bool GridMap::addDataFrom(const GridMap& other, bool extendMap, bool overwriteData,
00528 bool copyAllLayers, std::vector<std::string> layers)
00529 {
00530
00531 if (copyAllLayers) layers = other.getLayers();
00532
00533
00534 if (extendMap) extendToInclude(other);
00535
00536
00537 for (const auto& layer : layers) {
00538 if (std::find(layers_.begin(), layers_.end(), layer) == layers_.end()) {
00539 add(layer);
00540 }
00541 }
00542
00543 for (GridMapIterator iterator(*this); !iterator.isPastEnd(); ++iterator) {
00544 if (isValid(*iterator) && !overwriteData) continue;
00545 Position position;
00546 getPosition(*iterator, position);
00547 Index index;
00548 if (!other.isInside(position)) continue;
00549 other.getIndex(position, index);
00550 for (const auto& layer : layers) {
00551 if (!other.isValid(index, layer)) continue;
00552 at(layer, *iterator) = other.at(layer, index);
00553 }
00554 }
00555
00556 return true;
00557 }
00558
00559 bool GridMap::extendToInclude(const GridMap& other)
00560 {
00561
00562 Position topLeftCorner(position_.x() + length_.x() / 2.0, position_.y() + length_.y() / 2.0);
00563 Position bottomRightCorner(position_.x() - length_.x() / 2.0, position_.y() - length_.y() / 2.0);
00564 Position topLeftCornerOther(other.getPosition().x() + other.getLength().x() / 2.0, other.getPosition().y() + other.getLength().y() / 2.0);
00565 Position bottomRightCornerOther(other.getPosition().x() - other.getLength().x() / 2.0, other.getPosition().y() - other.getLength().y() / 2.0);
00566
00567 bool resizeMap = false;
00568 Position extendedMapPosition = position_;
00569 Length extendedMapLength = length_;
00570 if (topLeftCornerOther.x() > topLeftCorner.x()) {
00571 extendedMapPosition.x() += (topLeftCornerOther.x() - topLeftCorner.x()) / 2.0;
00572 extendedMapLength.x() += topLeftCornerOther.x() - topLeftCorner.x();
00573 resizeMap = true;
00574 }
00575 if (topLeftCornerOther.y() > topLeftCorner.y()) {
00576 extendedMapPosition.y() += (topLeftCornerOther.y() - topLeftCorner.y()) / 2.0;
00577 extendedMapLength.y() += topLeftCornerOther.y() - topLeftCorner.y();
00578 resizeMap = true;
00579 }
00580 if (bottomRightCornerOther.x() < bottomRightCorner.x()) {
00581 extendedMapPosition.x() -= (bottomRightCorner.x() - bottomRightCornerOther.x()) / 2.0;
00582 extendedMapLength.x() += bottomRightCorner.x() - bottomRightCornerOther.x();
00583 resizeMap = true;
00584 }
00585 if (bottomRightCornerOther.y() < bottomRightCorner.y()) {
00586 extendedMapPosition.y() -= (bottomRightCorner.y() - bottomRightCornerOther.y()) / 2.0;
00587 extendedMapLength.y() += bottomRightCorner.y() - bottomRightCornerOther.y();
00588 resizeMap = true;
00589 }
00590
00591 if (resizeMap) {
00592 GridMap mapCopy = *this;
00593 setGeometry(extendedMapLength, resolution_, extendedMapPosition);
00594
00595 Vector shift = position_ - mapCopy.getPosition();
00596 shift.x() = std::fmod(shift.x(), resolution_);
00597 shift.y() = std::fmod(shift.y(), resolution_);
00598 if (std::abs(shift.x()) < resolution_ / 2.0) {
00599 position_.x() -= shift.x();
00600 } else {
00601 position_.x() += resolution_ - shift.x();
00602 }
00603 if (size_.x() % 2 != mapCopy.getSize().x() % 2) {
00604 position_.x() += -std::copysign(resolution_ / 2.0, shift.x());
00605 }
00606 if (std::abs(shift.y()) < resolution_ / 2.0) {
00607 position_.y() -= shift.y();
00608 } else {
00609 position_.y() += resolution_ - shift.y();
00610 }
00611 if (size_.y() % 2 != mapCopy.getSize().y() % 2) {
00612 position_.y() += -std::copysign(resolution_ / 2.0, shift.y());
00613 }
00614
00615 for (GridMapIterator iterator(*this); !iterator.isPastEnd(); ++iterator) {
00616 if (isValid(*iterator)) continue;
00617 Position position;
00618 getPosition(*iterator, position);
00619 Index index;
00620 if (!mapCopy.isInside(position)) continue;
00621 mapCopy.getIndex(position, index);
00622 for (const auto& layer : layers_) {
00623 at(layer, *iterator) = mapCopy.at(layer, index);
00624 }
00625 }
00626 }
00627 return true;
00628 }
00629
00630 void GridMap::setTimestamp(const Time timestamp)
00631 {
00632 timestamp_ = timestamp;
00633 }
00634
00635 Time GridMap::getTimestamp() const
00636 {
00637 return timestamp_;
00638 }
00639
00640 void GridMap::resetTimestamp()
00641 {
00642 timestamp_ = 0.0;
00643 }
00644
00645 void GridMap::setFrameId(const std::string& frameId)
00646 {
00647 frameId_ = frameId;
00648 }
00649
00650 const std::string& GridMap::getFrameId() const
00651 {
00652 return frameId_;
00653 }
00654
00655 const Length& GridMap::getLength() const
00656 {
00657 return length_;
00658 }
00659
00660 const Position& GridMap::getPosition() const
00661 {
00662 return position_;
00663 }
00664
00665 double GridMap::getResolution() const
00666 {
00667 return resolution_;
00668 }
00669
00670 const Size& GridMap::getSize() const
00671 {
00672 return size_;
00673 }
00674
00675 void GridMap::setStartIndex(const Index& startIndex) {
00676 startIndex_ = startIndex;
00677 }
00678
00679 const Index& GridMap::getStartIndex() const
00680 {
00681 return startIndex_;
00682 }
00683
00684 bool GridMap::isDefaultStartIndex() const
00685 {
00686 return (startIndex_ == 0).all();
00687 }
00688
00689 void GridMap::convertToDefaultStartIndex()
00690 {
00691 if (isDefaultStartIndex()) return;
00692
00693 std::vector<BufferRegion> bufferRegions;
00694 if (!getBufferRegionsForSubmap(bufferRegions, startIndex_, size_, size_, startIndex_)) {
00695 throw std::out_of_range("Cannot access submap of this size.");
00696 }
00697
00698 for (auto& data : data_) {
00699 auto tempData(data.second);
00700 for (const auto& bufferRegion : bufferRegions) {
00701 Index index = bufferRegion.getStartIndex();
00702 Size size = bufferRegion.getSize();
00703
00704 if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::TopLeft) {
00705 tempData.topLeftCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
00706 } else if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::TopRight) {
00707 tempData.topRightCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
00708 } else if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::BottomLeft) {
00709 tempData.bottomLeftCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
00710 } else if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::BottomRight) {
00711 tempData.bottomRightCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
00712 }
00713 }
00714 data.second = tempData;
00715 }
00716
00717 startIndex_.setZero();
00718 }
00719
00720 void GridMap::clear(const std::string& layer)
00721 {
00722 try {
00723 data_.at(layer).setConstant(NAN);
00724 } catch (const std::out_of_range& exception) {
00725 throw std::out_of_range("GridMap::clear(...) : No map layer '" + layer + "' available.");
00726 }
00727 }
00728
00729 void GridMap::clearBasic()
00730 {
00731 for (auto& layer : basicLayers_) {
00732 clear(layer);
00733 }
00734 }
00735
00736 void GridMap::clearAll()
00737 {
00738 for (auto& data : data_) {
00739 data.second.setConstant(NAN);
00740 }
00741 }
00742
00743 void GridMap::clearRows(unsigned int index, unsigned int nRows)
00744 {
00745 std::vector<std::string> layersToClear;
00746 if (basicLayers_.size() > 0) layersToClear = basicLayers_;
00747 else layersToClear = layers_;
00748 for (auto& layer : layersToClear) {
00749 data_.at(layer).block(index, 0, nRows, getSize()(1)).setConstant(NAN);
00750 }
00751 }
00752
00753 void GridMap::clearCols(unsigned int index, unsigned int nCols)
00754 {
00755 std::vector<std::string> layersToClear;
00756 if (basicLayers_.size() > 0) layersToClear = basicLayers_;
00757 else layersToClear = layers_;
00758 for (auto& layer : layersToClear) {
00759 data_.at(layer).block(0, index, getSize()(0), nCols).setConstant(NAN);
00760 }
00761 }
00762
00763 bool GridMap::atPositionLinearInterpolated(const std::string& layer, const Position& position,
00764 float& value) const
00765 {
00766 Position point;
00767 Index indices[4];
00768 bool idxTempDir;
00769 size_t idxShift[4];
00770
00771 getIndex(position, indices[0]);
00772 getPosition(indices[0], point);
00773
00774 if (position.x() >= point.x()) {
00775 indices[1] = indices[0] + Index(-1, 0);
00776 idxTempDir = true;
00777 } else {
00778 indices[1] = indices[0] + Index(+1, 0);
00779 idxTempDir = false;
00780 }
00781 if (position.y() >= point.y()) {
00782 indices[2] = indices[0] + Index(0, -1);
00783 if(idxTempDir){ idxShift[0]=0; idxShift[1]=1; idxShift[2]=2; idxShift[3]=3; }
00784 else { idxShift[0]=1; idxShift[1]=0; idxShift[2]=3; idxShift[3]=2; }
00785
00786
00787 } else {
00788 indices[2] = indices[0] + Index(0, +1);
00789 if(idxTempDir){ idxShift[0]=2; idxShift[1]=3; idxShift[2]=0; idxShift[3]=1; }
00790 else { idxShift[0]=3; idxShift[1]=2; idxShift[2]=1; idxShift[3]=0; }
00791 }
00792 indices[3].x() = indices[1].x();
00793 indices[3].y() = indices[2].y();
00794
00795 const Size& mapSize = getSize();
00796 const size_t bufferSize = mapSize(0) * mapSize(1);
00797 const size_t startIndexLin = getLinearIndexFromIndex(startIndex_, mapSize);
00798 const size_t endIndexLin = startIndexLin + bufferSize;
00799 const auto& layerMat = operator[](layer);
00800 float f[4];
00801
00802 for (size_t i = 0; i < 4; ++i) {
00803 const size_t indexLin = getLinearIndexFromIndex(indices[idxShift[i]], mapSize);
00804 if ((indexLin < startIndexLin) || (indexLin > endIndexLin)) return false;
00805 f[i] = layerMat(indexLin);
00806 }
00807
00808 getPosition(indices[idxShift[0]], point);
00809 const Position positionRed = ( position - point ) / resolution_;
00810 const Position positionRedFlip = Position(1.,1.) - positionRed;
00811
00812 value = f[0] * positionRedFlip.x() * positionRedFlip.y() +
00813 f[1] * positionRed.x() * positionRedFlip.y() +
00814 f[2] * positionRedFlip.x() * positionRed.y() +
00815 f[3] * positionRed.x() * positionRed.y();
00816 return true;
00817 }
00818
00819 void GridMap::resize(const Index& size)
00820 {
00821 size_ = size;
00822 for (auto& data : data_) {
00823 data.second.resize(size_(0), size_(1));
00824 }
00825 }
00826
00827 }
00828