17 #include <unordered_map>    21 #include <Eigen/Geometry>    51   GridMap(
const std::vector<std::string>& layers);
    78                    const Position& position = Position::Zero());
    91   void add(
const std::string& layer, 
const double value = NAN);
    98   void add(
const std::string& layer, 
const Matrix& data);
   105   bool exists(
const std::string& layer) 
const;
   113   const Matrix& 
get(
const std::string& layer) 
const;
   122   Matrix& 
get(
const std::string& layer);
   130   const Matrix& 
operator [](
const std::string& layer) 
const;
   146   bool erase(
const std::string& layer);
   152   const std::vector<std::string>& 
getLayers() 
const;
   210   float& 
at(
const std::string& layer, 
const Index& index);
   219   float at(
const std::string& layer, 
const Index& index) 
const;
   259   bool isValid(
const Index& index, 
const std::string& layer) 
const;
   267   bool isValid(
const Index& index, 
const std::vector<std::string>& layers) 
const;
   286   bool getVector(
const std::string& layerPrefix, 
const Index& index,
   287                  Eigen::Vector3d& vector) 
const;
   313                     bool& isSuccess) 
const;
   329                             const std::string& newFrameId,
   330                             const double sampleRatio = 0.0) 
const;
   352   bool move(
const Position& position, std::vector<BufferRegion>& newRegions);
   373                    bool overwriteData, 
bool copyAllLayers,
   374                    std::vector<std::string> layers = std::vector<std::string>());
   387   void clear(
const std::string& layer);
   486   void clearCols(
unsigned int index, 
unsigned int nCols);
   493   void clearRows(
unsigned int index, 
unsigned int nRows);
   517   std::unordered_map<std::string, Matrix> 
data_;
   543   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 const Length & getLength() 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)
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. 
grid_map::DataType DataType
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 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 
Eigen::Vector3d Position3
bool exists(const std::string &layer) const 
bool extendToInclude(const GridMap &other)
double getResolution() const 
const std::vector< std::string > & getLayers() const 
std::vector< std::string > layers_
Names of the data layers. 
bool isInside(const Position &position) const 
bool isDefaultStartIndex() 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)
bool atPositionLinearInterpolated(const std::string &layer, const Position &position, float &value) const 
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]. 
void setFrameId(const std::string &frameId)
GridMap & operator=(const GridMap &)=default
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