00001
00005 #include <grid_map_core/GridMapMath.hpp>
00006 #include <cost_map_core/cost_map.hpp>
00007 #include <cost_map_core/iterators/costmap_iterator.hpp>
00008 #include <iostream>
00009 #include <cassert>
00010 #include <math.h>
00011 #include <algorithm>
00012 #include <stdexcept>
00013 #include "../include/cost_map_core/submap_geometry.hpp"
00014
00015 #include <Eigen/Dense>
00016
00017 namespace cost_map {
00018
00019 CostMap::CostMap(const std::vector<std::string>& layers)
00020 {
00021 position_.setZero();
00022 length_.setZero();
00023 resolution_ = 0.0;
00024 size_.setZero();
00025 startIndex_.setZero();
00026 timestamp_ = 0;
00027 layers_ = layers;
00028
00029 for (auto& layer : layers_) {
00030 data_.insert(std::pair<std::string, Matrix>(layer, Matrix()));
00031 }
00032 }
00033
00034 CostMap::CostMap() :
00035 CostMap(std::vector<std::string>())
00036 {
00037 }
00038
00039 CostMap::~CostMap()
00040 {
00041 }
00042
00043 void CostMap::setGeometry(const cost_map::Length& length, const double resolution,
00044 const cost_map::Position& position)
00045 {
00046 assert(length(0) > 0.0);
00047 assert(length(1) > 0.0);
00048 assert(resolution > 0.0);
00049
00050 Size size;
00051 size(0) = static_cast<int>(round(length(0) / resolution));
00052 size(1) = static_cast<int>(round(length(1) / resolution));
00053 resize(size);
00054 clearAll();
00055
00056 resolution_ = resolution;
00057 length_ = (size_.cast<double>() * resolution_).matrix();
00058 position_ = position;
00059 startIndex_.setZero();
00060
00061 return;
00062 }
00063
00064 void CostMap::setGeometry(const SubmapGeometry& geometry)
00065 {
00066 setGeometry(geometry.getLength(), geometry.getResolution(), geometry.getPosition());
00067 }
00068
00069 void CostMap::setBasicLayers(const std::vector<std::string>& basicLayers)
00070 {
00071 basicLayers_ = basicLayers;
00072 }
00073
00074 const std::vector<std::string>& CostMap::getBasicLayers() const
00075 {
00076 return basicLayers_;
00077 }
00078
00079 bool CostMap::hasSameLayers(const cost_map::CostMap& other) const
00080 {
00081 for (const auto& layer : layers_) {
00082 if (!other.exists(layer)) return false;
00083 }
00084 return true;
00085 }
00086
00087 void CostMap::add(const std::string& layer, const DataType value)
00088 {
00089 add(layer, Matrix::Constant(size_(0), size_(1), value));
00090 }
00091
00092 void CostMap::add(const std::string& layer, const Matrix& data)
00093 {
00094 assert(size_(0) == data.rows());
00095 assert(size_(1) == data.cols());
00096
00097 if (exists(layer)) {
00098
00099 data_.at(layer) = data;
00100 } else {
00101
00102 data_.insert(std::pair<std::string, Matrix>(layer, data));
00103 layers_.push_back(layer);
00104 }
00105 }
00106
00107 bool CostMap::exists(const std::string& layer) const
00108 {
00109 return !(data_.find(layer) == data_.end());
00110 }
00111
00112 const cost_map::Matrix& CostMap::get(const std::string& layer) const
00113 {
00114 try {
00115 return data_.at(layer);
00116 } catch (const std::out_of_range& exception) {
00117 throw std::out_of_range("CostMap::get(...) : No map layer '" + layer + "' available.");
00118 }
00119 }
00120
00121 cost_map::Matrix& CostMap::get(const std::string& layer)
00122 {
00123 try {
00124 return data_.at(layer);
00125 } catch (const std::out_of_range& exception) {
00126 throw std::out_of_range("CostMap::get(...) : No map layer of type '" + layer + "' available.");
00127 }
00128 }
00129
00130 const cost_map::Matrix& CostMap::operator [](const std::string& layer) const
00131 {
00132 return get(layer);
00133 }
00134
00135 cost_map::Matrix& CostMap::operator [](const std::string& layer)
00136 {
00137 return get(layer);
00138 }
00139
00140 bool CostMap::erase(const std::string& layer)
00141 {
00142 const auto dataIterator = data_.find(layer);
00143 if (dataIterator == data_.end()) return false;
00144 data_.erase(dataIterator);
00145
00146 const auto layerIterator = std::find(layers_.begin(), layers_.end(), layer);
00147 if (layerIterator == layers_.end()) return false;
00148 layers_.erase(layerIterator);
00149
00150 const auto basicLayerIterator = std::find(basicLayers_.begin(), basicLayers_.end(), layer);
00151 if (basicLayerIterator != basicLayers_.end()) basicLayers_.erase(basicLayerIterator);
00152
00153 return true;
00154 }
00155
00156 const std::vector<std::string>& CostMap::getLayers() const
00157 {
00158 return layers_;
00159 }
00160
00161 DataType& CostMap::atPosition(const std::string& layer, const cost_map::Position& position)
00162 {
00163 Eigen::Array2i index;
00164 if (getIndex(position, index)) {
00165 return at(layer, index);
00166 }
00167 throw std::out_of_range("CostMap::atPosition(...) : Position is out of range.");
00168 }
00169
00170 DataType CostMap::atPosition(const std::string& layer,
00171 const cost_map::Position& position,
00172 grid_map::InterpolationMethods interpolation_method
00173 ) const
00174 {
00175 if ( interpolation_method == grid_map::InterpolationMethods::INTER_LINEAR) {
00176 float value;
00177 if (atPositionLinearInterpolated(layer, position, value)) {
00178 return value;
00179 } else {
00180 interpolation_method = grid_map::InterpolationMethods::INTER_NEAREST;
00181 }
00182 }
00183 if ( interpolation_method == grid_map::InterpolationMethods::INTER_NEAREST)
00184 {
00185 Index index;
00186 if (getIndex(position, index)) {
00187 return at(layer, index);
00188 } else {
00189 throw std::out_of_range("CostMap::atPosition(...) : position is out of range.");
00190 }
00191 }
00192
00193 throw std::runtime_error("CostMap::atPosition(...) : specified interpolation method not implemented.");
00194 }
00195
00196 DataType& CostMap::at(const std::string& layer, const cost_map::Index& index)
00197 {
00198 try {
00199 return data_.at(layer)(index(0), index(1));
00200 } catch (const std::out_of_range& exception) {
00201 throw std::out_of_range("CostMap::at(...) : No map layer '" + layer + "' available.");
00202 }
00203 }
00204
00205 DataType CostMap::at(const std::string& layer, const Eigen::Array2i& index) const
00206 {
00207 try {
00208 return data_.at(layer)(index(0), index(1));
00209 } catch (const std::out_of_range& exception) {
00210 throw std::out_of_range("CostMap::at(...) : No map layer '" + layer + "' available.");
00211 }
00212 }
00213
00214 bool CostMap::getIndex(const cost_map::Position& position, cost_map::Index& index) const
00215 {
00216 return grid_map::getIndexFromPosition(index, position, length_, position_, resolution_, size_, startIndex_);
00217 }
00218
00219 bool CostMap::getPosition(const cost_map::Index& index, cost_map::Position& position) const
00220 {
00221 return grid_map::getPositionFromIndex(position, index, length_, position_, resolution_, size_, startIndex_);
00222 }
00223
00224 bool CostMap::isInside(const cost_map::Position& position) const
00225 {
00226 return grid_map::checkIfPositionWithinMap(position, length_, position_);
00227 }
00228
00229 bool CostMap::isValid(const cost_map::Index& index) const
00230 {
00231 return isValid(index, basicLayers_);
00232 }
00233
00234 bool CostMap::isValid(const cost_map::Index& index, const std::string& layer) const
00235 {
00236 return (at(layer, index) != NO_INFORMATION);
00237 }
00238
00239 bool CostMap::isValid(const cost_map::Index& index, const std::vector<std::string>& layers) const
00240 {
00241 if (layers.empty()) return false;
00242 for (auto& layer : layers) {
00243 if (at(layer, index) == NO_INFORMATION) return false;
00244 }
00245 return true;
00246 }
00247
00248 bool CostMap::getPosition3(const std::string& layer, const cost_map::Index& index,
00249 cost_map::Position3& position) const
00250 {
00251 if (!isValid(index, layer)) return false;
00252 Position position2d;
00253 getPosition(index, position2d);
00254 position.head(2) = position2d;
00255 position.z() = at(layer, index);
00256 return true;
00257 }
00258
00259 bool CostMap::getVector(const std::string& layerPrefix, const cost_map::Index& index,
00260 Eigen::Vector3d& vector) const
00261 {
00262 std::vector<std::string> layers;
00263 layers.push_back(layerPrefix + "x");
00264 layers.push_back(layerPrefix + "y");
00265 layers.push_back(layerPrefix + "z");
00266 if (!isValid(index, layers)) return false;
00267 for (size_t i = 0; i < 3; ++i) {
00268 vector(i) = at(layers[i], index);
00269 }
00270 return true;
00271 }
00272
00273 CostMap CostMap::getSubmap(const cost_map::Position& position, const cost_map::Length& length,
00274 bool& isSuccess) const
00275 {
00276 Index index;
00277 return getSubmap(position, length, index, isSuccess);
00278 }
00279
00280 CostMap CostMap::getSubmap(const cost_map::Position& position, const cost_map::Length& length,
00281 cost_map::Index& indexInSubmap, bool& isSuccess) const
00282 {
00283
00284 CostMap submap(layers_);
00285 submap.setBasicLayers(basicLayers_);
00286 submap.setTimestamp(timestamp_);
00287 submap.setFrameId(frameId_);
00288
00289
00290 SubmapGeometry submapInformation(*this, position, length, isSuccess);
00291 if (isSuccess == false) return CostMap(layers_);
00292 submap.setGeometry(submapInformation);
00293 submap.startIndex_.setZero();
00294
00295
00296 std::vector<BufferRegion> bufferRegions;
00297
00298 if (!getBufferRegionsForSubmap(bufferRegions, submapInformation.getStartIndex(),
00299 submap.getSize(), size_, startIndex_)) {
00300 std::cout << "Cannot access submap of this size." << std::endl;
00301 isSuccess = false;
00302 return CostMap(layers_);
00303 }
00304
00305 for (auto& data : data_) {
00306 for (const auto& bufferRegion : bufferRegions) {
00307 Index index = bufferRegion.getStartIndex();
00308 Size size = bufferRegion.getSize();
00309
00310 if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::TopLeft) {
00311 submap.data_[data.first].topLeftCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
00312 } else if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::TopRight) {
00313 submap.data_[data.first].topRightCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
00314 } else if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::BottomLeft) {
00315 submap.data_[data.first].bottomLeftCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
00316 } else if (bufferRegion.getQuadrant() == BufferRegion::Quadrant::BottomRight) {
00317 submap.data_[data.first].bottomRightCorner(size(0), size(1)) = data.second.block(index(0), index(1), size(0), size(1));
00318 }
00319
00320 }
00321 }
00322
00323 isSuccess = true;
00324 return submap;
00325 }
00326
00327 bool CostMap::move(const cost_map::Position& position, std::vector<BufferRegion>& newRegions)
00328 {
00329 Index indexShift;
00330 Position positionShift = position - position_;
00331 grid_map::getIndexShiftFromPositionShift(indexShift, positionShift, resolution_);
00332 Position alignedPositionShift;
00333 grid_map::getPositionShiftFromIndexShift(alignedPositionShift, indexShift, resolution_);
00334
00335
00336 for (int i = 0; i < indexShift.size(); i++) {
00337 if (indexShift(i) != 0) {
00338 if (abs(indexShift(i)) >= getSize()(i)) {
00339
00340 clearAll();
00341 newRegions.push_back(BufferRegion(Index(0, 0), getSize(), BufferRegion::Quadrant::Undefined));
00342 } else {
00343
00344 int sign = (indexShift(i) > 0 ? 1 : -1);
00345 int startIndex = startIndex_(i) - (sign < 0 ? 1 : 0);
00346 int endIndex = startIndex - sign + indexShift(i);
00347 int nCells = abs(indexShift(i));
00348 int index = (sign > 0 ? startIndex : endIndex);
00349 grid_map::boundIndexToRange(index, getSize()(i));
00350
00351 if (index + nCells <= getSize()(i)) {
00352
00353 if (i == 0) {
00354 clearRows(index, nCells);
00355 newRegions.push_back(BufferRegion(Index(index, 0), Size(nCells, getSize()(1)), BufferRegion::Quadrant::Undefined));
00356 } else if (i == 1) {
00357 clearCols(index, nCells);
00358 newRegions.push_back(BufferRegion(Index(0, index), Size(getSize()(0), nCells), BufferRegion::Quadrant::Undefined));
00359 }
00360 } else {
00361
00362 int firstIndex = index;
00363 int firstNCells = getSize()(i) - firstIndex;
00364 if (i == 0) {
00365 clearRows(firstIndex, firstNCells);
00366 newRegions.push_back(BufferRegion(Index(firstIndex, 0), Size(firstNCells, getSize()(1)), BufferRegion::Quadrant::Undefined));
00367 } else if (i == 1) {
00368 clearCols(firstIndex, firstNCells);
00369 newRegions.push_back(BufferRegion(Index(0, firstIndex), Size(getSize()(0), firstNCells), BufferRegion::Quadrant::Undefined));
00370 }
00371
00372 int secondIndex = 0;
00373 int secondNCells = nCells - firstNCells;
00374 if (i == 0) {
00375 clearRows(secondIndex, secondNCells);
00376 newRegions.push_back(BufferRegion(Index(secondIndex, 0), Size(secondNCells, getSize()(1)), BufferRegion::Quadrant::Undefined));
00377 } else if (i == 1) {
00378 clearCols(secondIndex, secondNCells);
00379 newRegions.push_back(BufferRegion(Index(0, secondIndex), Size(getSize()(0), secondNCells), BufferRegion::Quadrant::Undefined));
00380 }
00381 }
00382 }
00383 }
00384 }
00385
00386
00387 startIndex_ += indexShift;
00388 grid_map::boundIndexToRange(startIndex_, getSize());
00389 position_ += alignedPositionShift;
00390
00391
00392 return (indexShift.any() != 0);
00393 }
00394
00395 bool CostMap::move(const cost_map::Position& position)
00396 {
00397 std::vector<BufferRegion> newRegions;
00398 return move(position, newRegions);
00399 }
00400
00401 bool CostMap::addDataFrom(const cost_map::CostMap& other, bool extendMap, bool overwriteData,
00402 bool copyAllLayers, std::vector<std::string> layers)
00403 {
00404
00405 if (copyAllLayers) layers = other.getLayers();
00406
00407
00408 if (extendMap) extendToInclude(other);
00409
00410
00411 for (const auto& layer : layers) {
00412 if (std::find(layers_.begin(), layers_.end(), layer) == layers_.end()) {
00413 add(layer);
00414 }
00415 }
00416
00417 for (CostMapIterator iterator(*this); !iterator.isPastEnd(); ++iterator) {
00418 if (isValid(*iterator) && !overwriteData) continue;
00419 Position position;
00420 getPosition(*iterator, position);
00421 Index index;
00422 if (!other.isInside(position)) continue;
00423 other.getIndex(position, index);
00424 for (const auto& layer : layers) {
00425 if (!other.isValid(index, layer)) continue;
00426 at(layer, *iterator) = other.at(layer, index);
00427 }
00428 }
00429
00430 return true;
00431 }
00432
00433 bool CostMap::extendToInclude(const cost_map::CostMap& other)
00434 {
00435
00436 Position topLeftCorner(position_.x() + length_.x() / 2.0, position_.y() + length_.y() / 2.0);
00437 Position bottomRightCorner(position_.x() - length_.x() / 2.0, position_.y() - length_.y() / 2.0);
00438 Position topLeftCornerOther(other.getPosition().x() + other.getLength().x() / 2.0, other.getPosition().y() + other.getLength().y() / 2.0);
00439 Position bottomRightCornerOther(other.getPosition().x() - other.getLength().x() / 2.0, other.getPosition().y() - other.getLength().y() / 2.0);
00440
00441 bool resizeMap = false;
00442 Position extendedMapPosition = position_;
00443 Length extendedMapLength = length_;
00444 if (topLeftCornerOther.x() > topLeftCorner.x()) {
00445 extendedMapPosition.x() += (topLeftCornerOther.x() - topLeftCorner.x()) / 2.0;
00446 extendedMapLength.x() += topLeftCornerOther.x() - topLeftCorner.x();
00447 resizeMap = true;
00448 }
00449 if (topLeftCornerOther.y() > topLeftCorner.y()) {
00450 extendedMapPosition.y() += (topLeftCornerOther.y() - topLeftCorner.y()) / 2.0;
00451 extendedMapLength.y() += topLeftCornerOther.y() - topLeftCorner.y();
00452 resizeMap = true;
00453 }
00454 if (bottomRightCornerOther.x() < bottomRightCorner.x()) {
00455 extendedMapPosition.x() -= (bottomRightCorner.x() - bottomRightCornerOther.x()) / 2.0;
00456 extendedMapLength.x() += bottomRightCorner.x() - bottomRightCornerOther.x();
00457 resizeMap = true;
00458 }
00459 if (bottomRightCornerOther.y() < bottomRightCorner.y()) {
00460 extendedMapPosition.y() -= (bottomRightCorner.y() - bottomRightCornerOther.y()) / 2.0;
00461 extendedMapLength.y() += bottomRightCorner.y() - bottomRightCornerOther.y();
00462 resizeMap = true;
00463 }
00464
00465
00466 if (resizeMap) {
00467 CostMap mapCopy = *this;
00468 setGeometry(extendedMapLength, resolution_, extendedMapPosition);
00469
00470 Vector shift = position_ - mapCopy.getPosition();
00471 shift.x() = std::fmod(shift.x(), resolution_);
00472 shift.y() = std::fmod(shift.y(), resolution_);
00473 if (std::abs(shift.x()) < resolution_ / 2.0) {
00474 position_.x() -= shift.x();
00475 } else {
00476 position_.x() += resolution_ - shift.x();
00477 }
00478 if (size_.x() % 2 != mapCopy.getSize().x() % 2) {
00479 position_.x() += -std::copysign(resolution_ / 2.0, shift.x());
00480 }
00481 if (std::abs(shift.y()) < resolution_ / 2.0) {
00482 position_.y() -= shift.y();
00483 } else {
00484 position_.y() += resolution_ - shift.y();
00485 }
00486 if (size_.y() % 2 != mapCopy.getSize().y() % 2) {
00487 position_.y() += -std::copysign(resolution_ / 2.0, shift.y());
00488 }
00489
00490 for (CostMapIterator iterator(*this); !iterator.isPastEnd(); ++iterator) {
00491 if (isValid(*iterator)) continue;
00492 Position position;
00493 getPosition(*iterator, position);
00494 Index index;
00495 if (!mapCopy.isInside(position)) continue;
00496 mapCopy.getIndex(position, index);
00497 for (const auto& layer : layers_) {
00498 at(layer, *iterator) = mapCopy.at(layer, index);
00499 }
00500 }
00501 }
00502 return true;
00503 }
00504
00505 void CostMap::setTimestamp(const Time timestamp)
00506 {
00507 timestamp_ = timestamp;
00508 }
00509
00510 Time CostMap::getTimestamp() const
00511 {
00512 return timestamp_;
00513 }
00514
00515 void CostMap::resetTimestamp()
00516 {
00517 timestamp_ = 0.0;
00518 }
00519
00520 void CostMap::setFrameId(const std::string& frameId)
00521 {
00522 frameId_ = frameId;
00523 }
00524
00525 const std::string& CostMap::getFrameId() const
00526 {
00527 return frameId_;
00528 }
00529
00530 const Eigen::Array2d& CostMap::getLength() const
00531 {
00532 return length_;
00533 }
00534
00535 const Eigen::Vector2d& CostMap::getPosition() const
00536 {
00537 return position_;
00538 }
00539
00540 double CostMap::getResolution() const
00541 {
00542 return resolution_;
00543 }
00544
00545 const cost_map::Size& CostMap::getSize() const
00546 {
00547 return size_;
00548 }
00549
00550 void CostMap::setStartIndex(const cost_map::Index& startIndex) {
00551 startIndex_ = startIndex;
00552 }
00553
00554 const cost_map::Index& CostMap::getStartIndex() const
00555 {
00556 return startIndex_;
00557 }
00558
00559 void CostMap::clear(const std::string& layer)
00560 {
00561 try {
00562 data_.at(layer).setConstant(NO_INFORMATION);
00563 } catch (const std::out_of_range& exception) {
00564 throw std::out_of_range("CostMap::clear(...) : No map layer '" + layer + "' available.");
00565 }
00566 }
00567
00568 void CostMap::clearBasic()
00569 {
00570 for (auto& layer : basicLayers_) {
00571 clear(layer);
00572 }
00573 }
00574
00575 void CostMap::clearAll()
00576 {
00577 for (auto& data : data_) {
00578 data.second.setConstant(NO_INFORMATION);
00579 }
00580 }
00581
00582 void CostMap::clearRows(unsigned int index, unsigned int nRows)
00583 {
00584 std::vector<std::string> layersToClear;
00585 if (basicLayers_.size() > 0) layersToClear = basicLayers_;
00586 else layersToClear = layers_;
00587 for (auto& layer : layersToClear) {
00588 data_.at(layer).block(index, 0, nRows, getSize()(1)).setConstant(NO_INFORMATION);
00589 }
00590 }
00591
00592 void CostMap::clearCols(unsigned int index, unsigned int nCols)
00593 {
00594 std::vector<std::string> layersToClear;
00595 if (basicLayers_.size() > 0) layersToClear = basicLayers_;
00596 else layersToClear = layers_;
00597 for (auto& layer : layersToClear) {
00598 data_.at(layer).block(0, index, getSize()(0), nCols).setConstant(NO_INFORMATION);
00599 }
00600 }
00601
00602 bool CostMap::atPositionLinearInterpolated(const std::string& layer, const Position& position,
00603 float& value) const
00604 {
00605 std::vector<Position> points(4);
00606 std::vector<Index> indices(4);
00607 getIndex(position, indices[0]);
00608 getPosition(indices[0], points[0]);
00609
00610 if (position.x() >= points[0].x()) {
00611
00612 indices[1] = indices[0] + Index(-1, 0);
00613 if (!getPosition(indices[1], points[1])) return false;
00614 } else {
00615 indices[1] = indices[0] + Index(1, 0);
00616 if (!getPosition(indices[1], points[1])) return false;
00617 }
00618
00619 if (position.y() >= points[0].y()) {
00620
00621 indices[2] = indices[0] + Index(0, -1);
00622 if (!getPosition(indices[2], points[2])) return false;
00623 } else {
00624 indices[2] = indices[0] + Index(0, 1);
00625 if (!getPosition(indices[2], points[2])) return false;
00626 }
00627
00628 indices[3].x() = indices[1].x();
00629 indices[3].y() = indices[2].y();
00630 if (!getPosition(indices[3], points[3])) return false;
00631
00632 Eigen::Vector4d b;
00633 Eigen::Matrix4d A;
00634
00635 for (unsigned int i = 0; i < points.size(); ++i) {
00636 b(i) = at(layer, indices[i]);
00637 A.row(i) << 1, points[i].x(), points[i].y(), points[i].x() * points[i].y();
00638 }
00639
00640 Eigen::Vector4d x = A.colPivHouseholderQr().solve(b);
00641
00642
00643 value = x(0) + x(1) * position.x() + x(2) * position.y() + x(3) * position.x() * position.y();
00644 return true;
00645 }
00646
00647 void CostMap::resize(const Eigen::Array2i& size)
00648 {
00649 size_ = size;
00650 for (auto& data : data_) {
00651 data.second.resize(size_(0), size_(1));
00652 }
00653 }
00654
00655 }
00656