GridMap.hpp
Go to the documentation of this file.
00001 /*
00002  * GridMap.hpp
00003  *
00004  *  Created on: Jul 14, 2014
00005  *      Author: Péter Fankhauser
00006  *       Institute: ETH Zurich, Autonomous Systems Lab
00007  */
00008 
00009 #pragma once
00010 
00011 #include "grid_map_core/TypeDefs.hpp"
00012 #include "grid_map_core/SubmapGeometry.hpp"
00013 #include "grid_map_core/BufferRegion.hpp"
00014 
00015 // STL
00016 #include <vector>
00017 #include <unordered_map>
00018 
00019 // Eigen
00020 #include <Eigen/Core>
00021 
00022 namespace grid_map {
00023 
00024 class SubmapGeometry;
00025 
00039 class GridMap
00040 {
00041  public:
00042   // Type traits for use with template methods/classes using GridMap as a template parameter.
00043   typedef grid_map::DataType DataType;
00044   typedef grid_map::Matrix Matrix;
00045 
00050   GridMap(const std::vector<std::string>& layers);
00051 
00055   GridMap();
00056 
00060   GridMap(const GridMap&) = default;
00061   GridMap& operator=(const GridMap&) = default;
00062   GridMap(GridMap&&) = default;
00063   GridMap& operator=(GridMap&&) = default;
00064 
00068   virtual ~GridMap();
00069 
00076   void setGeometry(const Length& length, const double resolution,
00077                    const Position& position = Position::Zero());
00078 
00083   void setGeometry(const SubmapGeometry& geometry);
00084 
00090   void add(const std::string& layer, const double value = NAN);
00091 
00097   void add(const std::string& layer, const Matrix& data);
00098 
00104   bool exists(const std::string& layer) const;
00105 
00112   const Matrix& get(const std::string& layer) const;
00113 
00121   Matrix& get(const std::string& layer);
00122 
00129   const Matrix& operator [](const std::string& layer) const;
00130 
00138   Matrix& operator [](const std::string& layer);
00139 
00145   bool erase(const std::string& layer);
00146 
00151   const std::vector<std::string>& getLayers() const;
00152 
00159   void setBasicLayers(const std::vector<std::string>& basicLayers);
00160 
00165   const std::vector<std::string>& getBasicLayers() const;
00166 
00171   bool hasBasicLayers() const;
00172 
00180   bool hasSameLayers(const grid_map::GridMap& other) const;
00181 
00189   float& atPosition(const std::string& layer, const Position& position);
00190 
00199   float atPosition(const std::string& layer, const Position& position,
00200                    InterpolationMethods interpolationMethod = InterpolationMethods::INTER_NEAREST) const;
00201 
00209   float& at(const std::string& layer, const Index& index);
00210 
00218   float at(const std::string& layer, const Index& index) const;
00219 
00226   bool getIndex(const Position& position, Index& index) const;
00227 
00235   bool getPosition(const Index& index, Position& position) const;
00236 
00242   bool isInside(const Position& position) const;
00243 
00250   bool isValid(const Index& index) const;
00251 
00258   bool isValid(const Index& index, const std::string& layer) const;
00259 
00266   bool isValid(const Index& index, const std::vector<std::string>& layers) const;
00267 
00276   bool getPosition3(const std::string& layer, const Index& index, Position3& position) const;
00277 
00285   bool getVector(const std::string& layerPrefix, const Index& index,
00286                  Eigen::Vector3d& vector) const;
00287 
00298   GridMap getSubmap(const Position& position, const Length& length, bool& isSuccess) const;
00299 
00311   GridMap getSubmap(const Position& position, const Length& length, Index& indexInSubmap,
00312                     bool& isSuccess) const;
00313 
00322    void setPosition(const Position& position);
00323 
00334   bool move(const Position& position, std::vector<BufferRegion>& newRegions);
00335 
00343   bool move(const Position& position);
00344 
00354   bool addDataFrom(const GridMap& other, bool extendMap,
00355                    bool overwriteData, bool copyAllLayers,
00356                    std::vector<std::string> layers = std::vector<std::string>());
00357 
00363   bool extendToInclude(const GridMap& other);
00364 
00369   void clear(const std::string& layer);
00370 
00375   void clearBasic();
00376 
00382   void clearAll();
00383 
00388   void setTimestamp(const Time timestamp);
00389 
00394   Time getTimestamp() const;
00395 
00399   void resetTimestamp();
00400 
00405   void setFrameId(const std::string& frameId);
00406 
00411   const std::string& getFrameId() const;
00412 
00417   const Length& getLength() const;
00418 
00423   const Position& getPosition() const;
00424 
00429   double getResolution() const;
00430 
00435   const Size& getSize() const;
00436 
00442   void setStartIndex(const Index& startIndex);
00443 
00448   const Index& getStartIndex() const;
00449 
00454   bool isDefaultStartIndex() const;
00455 
00459   void convertToDefaultStartIndex();
00460 
00461  private:
00462 
00468   void clearCols(unsigned int index, unsigned int nCols);
00469 
00475   void clearRows(unsigned int index, unsigned int nRows);
00476 
00484   bool atPositionLinearInterpolated(const std::string& layer, const Position& position, float& value) const;
00485 
00490   void resize(const Index& bufferSize);
00491 
00493   std::string frameId_;
00494 
00496   Time timestamp_;
00497 
00499   std::unordered_map<std::string, Matrix> data_;
00500 
00502   std::vector<std::string> layers_;
00503 
00507   std::vector<std::string> basicLayers_;
00508 
00510   Length length_;
00511 
00513   double resolution_;
00514 
00516   Position position_;
00517 
00519   Size size_;
00520 
00522   Index startIndex_;
00523 
00524  public:
00525   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00526 };
00527 
00528 } /* namespace */


grid_map_core
Author(s): Péter Fankhauser
autogenerated on Mon Oct 9 2017 03:09:16