Namespaces | Classes | Typedefs | Enumerations | Functions
grid_map Namespace Reference

Namespaces

 bicubic
 
 bicubic_conv
 
 internal
 

Classes

class  BufferRegion
 
class  CircleIterator
 
struct  Clamp
 
union  Color
 
class  EllipseIterator
 
class  GridMap
 
class  GridMapIterator
 
class  LineIterator
 
class  Polygon
 
class  PolygonIterator
 
class  SlidingWindowIterator
 
class  SpiralIterator
 
class  SubmapGeometry
 
class  SubmapIterator
 

Typedefs

typedef Matrix::Scalar DataType
 
using FunctionValueMatrix = Eigen::Matrix4d
 
typedef Eigen::Array2i Index
 
typedef Eigen::Array2d Length
 
typedef Eigen::MatrixXf Matrix
 
typedef Eigen::Vector2d Position
 
typedef Eigen::Vector3d Position3
 
typedef Eigen::Array2i Size
 
typedef uint64_t Time
 
typedef Eigen::Vector2d Vector
 
typedef Eigen::Vector3d Vector3
 

Enumerations

enum  InterpolationMethods { InterpolationMethods::INTER_NEAREST, InterpolationMethods::INTER_LINEAR, InterpolationMethods::INTER_CUBIC_CONVOLUTION, InterpolationMethods::INTER_CUBIC }
 

Functions

template<typename M1 , typename M2 >
void assertEqual (const M1 &A, const M2 &B, std::string const &message="")
 
template<typename M1 >
void assertFinite (const M1 &A, std::string const &message="")
 
template<typename M1 , typename M2 , typename T >
void assertNear (const M1 &A, const M2 &B, T tolerance, std::string const &message="")
 
unsigned int bindIndexToRange (int idReq, unsigned int nElem)
 
void boundIndexToRange (Index &index, const Size &bufferSize)
 
void boundIndexToRange (int &index, const int &bufferSize)
 
void boundPositionToRange (Position &position, const Length &mapLength, const Position &mapPosition)
 
bool checkIfIndexInRange (const Index &index, const Size &bufferSize)
 
bool checkIfPositionWithinMap (const Position &position, const Length &mapLength, const Position &mapPosition)
 
bool colorValueToVector (const unsigned long &colorValue, Eigen::Vector3i &colorVector)
 
bool colorValueToVector (const unsigned long &colorValue, Eigen::Vector3f &colorVector)
 
bool colorValueToVector (const float &colorValue, Eigen::Vector3f &colorVector)
 
bool colorVectorToValue (const Eigen::Vector3i &colorVector, unsigned long &colorValue)
 
void colorVectorToValue (const Eigen::Vector3i &colorVector, float &colorValue)
 
void colorVectorToValue (const Eigen::Vector3f &colorVector, float &colorValue)
 
bool compareRelative (double a, double b, double percentTolerance, double *percentError=NULL)
 
template<typename M1 , typename M2 , typename T >
void expectNear (const M1 &A, const M2 &B, T tolerance, std::string const &message="")
 
Index getBufferIndexFromIndex (const Index &index, const Size &bufferSize, const Index &bufferStartIndex)
 
const Eigen::Matrix2i getBufferOrderToMapFrameAlignment ()
 
bool getBufferRegionsForSubmap (std::vector< BufferRegion > &submapBufferRegions, const Index &submapIndex, const Size &submapBufferSize, const Size &bufferSize, const Index &bufferStartIndex=Index::Zero())
 
Index getIndexFromBufferIndex (const Index &bufferIndex, const Size &bufferSize, const Index &bufferStartIndex)
 
Index getIndexFromLinearIndex (const size_t linearIndex, const Size &bufferSize, const bool rowMajor=false)
 
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 getIndexShiftFromPositionShift (Index &indexShift, const Vector &positionShift, const double &resolution)
 
double getLayerValue (const Matrix &layerMat, int rowReq, int colReq)
 
size_t getLinearIndexFromIndex (const Index &index, const Size &bufferSize, const bool rowMajor=false)
 
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 getPositionOfDataStructureOrigin (const Position &position, const Length &mapLength, Position &positionOfOrigin)
 
bool getPositionShiftFromIndexShift (Vector &positionShift, const Index &indexShift, const double &resolution)
 
bool getSubmapInformation (Index &submapTopLeftIndex, Size &submapBufferSize, Position &submapPosition, Length &submapLength, Index &requestedIndexInSubmap, const Position &requestedSubmapPosition, const Length &requestedSubmapLength, const Length &mapLength, const Position &mapPosition, const double &resolution, const Size &bufferSize, const Index &bufferStartIndex=Index::Zero())
 
Size getSubmapSizeFromCornerIndeces (const Index &topLeftIndex, const Index &bottomRightIndex, const Size &bufferSize, const Index &bufferStartIndex)
 
bool incrementIndex (Index &index, const Size &bufferSize, const Index &bufferStartIndex=Index::Zero())
 
bool incrementIndexForSubmap (Index &submapIndex, Index &index, const Index &submapTopLeftIndex, const Size &submapBufferSize, const Size &bufferSize, const Index &bufferStartIndex=Index::Zero())
 
template<int N>
Eigen::Matrix< double, N, N > randomCovariance ()
 
Eigen::MatrixXd randomCovarianceXd (int N)
 
void wrapIndexToRange (Index &index, const Size &bufferSize)
 
void wrapIndexToRange (int &index, int bufferSize)
 

Typedef Documentation

typedef Matrix::Scalar grid_map::DataType

Definition at line 17 of file TypeDefs.hpp.

using grid_map::FunctionValueMatrix = typedef Eigen::Matrix4d

Definition at line 40 of file CubicInterpolation.hpp.

typedef Eigen::Array2i grid_map::Index

Definition at line 22 of file TypeDefs.hpp.

typedef Eigen::Array2d grid_map::Length

Definition at line 24 of file TypeDefs.hpp.

typedef Eigen::MatrixXf grid_map::Matrix

Definition at line 16 of file TypeDefs.hpp.

typedef Eigen::Vector2d grid_map::Position

Definition at line 18 of file TypeDefs.hpp.

typedef Eigen::Vector3d grid_map::Position3

Definition at line 20 of file TypeDefs.hpp.

typedef Eigen::Array2i grid_map::Size

Definition at line 23 of file TypeDefs.hpp.

typedef uint64_t grid_map::Time

Definition at line 25 of file TypeDefs.hpp.

typedef Eigen::Vector2d grid_map::Vector

Definition at line 19 of file TypeDefs.hpp.

typedef Eigen::Vector3d grid_map::Vector3

Definition at line 21 of file TypeDefs.hpp.

Enumeration Type Documentation

Enumerator
INTER_NEAREST 
INTER_LINEAR 
INTER_CUBIC_CONVOLUTION 
INTER_CUBIC 

Definition at line 39 of file TypeDefs.hpp.

Function Documentation

template<typename M1 , typename M2 >
void grid_map::assertEqual ( const M1 &  A,
const M2 &  B,
std::string const &  message = "" 
)

Definition at line 33 of file gtest_eigen.hpp.

template<typename M1 >
void grid_map::assertFinite ( const M1 &  A,
std::string const &  message = "" 
)

Definition at line 99 of file gtest_eigen.hpp.

template<typename M1 , typename M2 , typename T >
void grid_map::assertNear ( const M1 &  A,
const M2 &  B,
tolerance,
std::string const &  message = "" 
)

Definition at line 54 of file gtest_eigen.hpp.

unsigned int grid_map::bindIndexToRange ( int  idReq,
unsigned int  nElem 
)

Takes the id requested, performs checks and returns an id that it is within the specified bounds.

Parameters
[in]idReq- input index .
[in]nElem- number of elements in the container
Returns
index that is within [0, nElem-1].

Definition at line 16 of file CubicInterpolation.cpp.

void grid_map::boundIndexToRange ( Index index,
const Size bufferSize 
)

Bounds an index that runs out of the range of the buffer. This means that an index that overflows is stopped at the last valid index. This is the 2d version of boundIndexToRange(int&, const int&).

Parameters

Definition at line 200 of file GridMapMath.cpp.

void grid_map::boundIndexToRange ( int &  index,
const int &  bufferSize 
)

Bounds an index that runs out of the range of the buffer. This means that an index that overflows is stopped at the last valid index.

Parameters

Definition at line 207 of file GridMapMath.cpp.

void grid_map::boundPositionToRange ( Position position,
const Length mapLength,
const Position mapPosition 
)

Bound (cuts off) the position to lie inside the map. This means that an index that overflows is stopped at the last valid index.

Parameters

Definition at line 241 of file GridMapMath.cpp.

bool grid_map::checkIfIndexInRange ( const Index index,
const Size bufferSize 
)

Checks if index is within range of the buffer.

Parameters
[in]indexto check.
[in]bufferSizethe size of the buffer.
Returns
true if index is within, and false if index is outside of the buffer.

Definition at line 191 of file GridMapMath.cpp.

bool grid_map::checkIfPositionWithinMap ( const Position position,
const Length mapLength,
const Position mapPosition 
)

Checks if position is within the map boundaries.

Parameters
[in]positionthe position which is to be checked.
[in]mapLengththe length of the map.
[in]mapPositionthe position of the map.
Returns
true if position is within map, false otherwise.

Definition at line 144 of file GridMapMath.cpp.

bool grid_map::colorValueToVector ( const unsigned long &  colorValue,
Eigen::Vector3i &  colorVector 
)

Transforms an int color value (concatenated RGB values) to an int color vector (RGB from 0-255).

Parameters
[in]colorValuethe concatenated RGB color value.
[out]colorVectorthe color vector in RGB from 0-255.
Returns
true if successful.

Definition at line 520 of file GridMapMath.cpp.

bool grid_map::colorValueToVector ( const unsigned long &  colorValue,
Eigen::Vector3f &  colorVector 
)

Transforms an int color value (concatenated RGB values) to a float color vector (RGB from 0.0-1.0).

Parameters
[in]colorValuethe concatenated RGB color value.
[out]colorVectorthe color vector in RGB from 0.0-1.0.
Returns
true if successful.

Definition at line 528 of file GridMapMath.cpp.

bool grid_map::colorValueToVector ( const float &  colorValue,
Eigen::Vector3f &  colorVector 
)

Transforms a float color value (concatenated 3 single-byte value) to a float color vector (RGB from 0.0-1.0).

Parameters
[in]colorValuethe concatenated RGB color value.
[out]colorVectorthe color vector in RGB from 0.0-1.0.
Returns
true if successful.

Definition at line 536 of file GridMapMath.cpp.

bool grid_map::colorVectorToValue ( const Eigen::Vector3i &  colorVector,
unsigned long &  colorValue 
)

Transforms an int color vector (RGB from 0-255) to a concatenated RGB int color.

Parameters
[in]colorVectorthe color vector in RGB from 0-255.
[out]colorValuethe concatenated RGB color value.
Returns
true if successful.

Definition at line 544 of file GridMapMath.cpp.

void grid_map::colorVectorToValue ( const Eigen::Vector3i &  colorVector,
float &  colorValue 
)

Transforms a color vector (RGB from 0-255) to a concatenated 3 single-byte float value.

Parameters
[in]colorVectorthe color vector in RGB from 0-255.
[out]colorValuethe concatenated RGB color value.

Definition at line 550 of file GridMapMath.cpp.

void grid_map::colorVectorToValue ( const Eigen::Vector3f &  colorVector,
float &  colorValue 
)

Transforms a color vector (RGB from 0.0-1.0) to a concatenated 3 single-byte float value.

Parameters
[in]colorVectorthe color vector in RGB from 0.0-1.0.
[out]colorValuethe concatenated RGB color value.

Definition at line 557 of file GridMapMath.cpp.

bool grid_map::compareRelative ( double  a,
double  b,
double  percentTolerance,
double *  percentError = NULL 
)
inline

Definition at line 110 of file gtest_eigen.hpp.

template<typename M1 , typename M2 , typename T >
void grid_map::expectNear ( const M1 &  A,
const M2 &  B,
tolerance,
std::string const &  message = "" 
)

Definition at line 78 of file gtest_eigen.hpp.

Index grid_map::getBufferIndexFromIndex ( const Index index,
const Size bufferSize,
const Index bufferStartIndex 
)

Retrieve the index of the buffer from a unwrapped index (reverse from function above).

Parameters
indexthe unwrapped index.
bufferSizethe map buffer size.
bufferStartIndexthe map buffer start index.
Returns
the buffer index.

Definition at line 499 of file GridMapMath.cpp.

const Eigen::Matrix2i grid_map::getBufferOrderToMapFrameAlignment ( )

Provides the alignment transformation from the buffer order (outer/inner storage) and the map frame (x/y-coordinate).

Returns
the alignment transformation.

Definition at line 266 of file GridMapMath.cpp.

bool grid_map::getBufferRegionsForSubmap ( std::vector< BufferRegion > &  submapBufferRegions,
const Index submapIndex,
const Size submapBufferSize,
const Size bufferSize,
const Index bufferStartIndex = Index::Zero() 
)

Computes the regions in the circular buffer that make up the data for a requested submap.

Parameters
[out]submapBufferRegionsthe list of buffer regions that make up the submap.
[in]submapIndexthe index (top-left) for the requested submap.
[in]submapBufferSizethe size of the requested submap.
[in]bufferSizethe buffer size of the map.
[in]bufferStartIndexthe index of the starting point of the circular buffer (optional).
Returns
true if successful, false if requested submap is not fully contained in the map.

Definition at line 329 of file GridMapMath.cpp.

Index grid_map::getIndexFromBufferIndex ( const Index bufferIndex,
const Size bufferSize,
const Index bufferStartIndex 
)

Retrieve the index as unwrapped index, i.e., as the corresponding index of a grid map with no circular buffer offset.

Parameters
bufferIndexthe index in the circular buffer.
bufferSizethe map buffer size.
bufferStartIndexthe map buffer start index.
Returns
the unwrapped index.

Definition at line 490 of file GridMapMath.cpp.

Index grid_map::getIndexFromLinearIndex ( const size_t  linearIndex,
const Size bufferSize,
const bool  rowMajor = false 
)

Returns the regular index (2-dim.) corresponding to the linear index (1-dim.) for a given buffer size.

Parameters
[in]linearIndexthe he linear 1d index.
[in]bufferSizethe map buffer size.
[in](optional)rowMajor if the linear index is generated for row-major format.
Returns
the regular 2d index.

Definition at line 514 of file GridMapMath.cpp.

bool grid_map::getIndexFromPosition ( Index index,
const Position position,
const Length mapLength,
const Position mapPosition,
const double &  resolution,
const Size bufferSize,
const Index bufferStartIndex = Index::Zero() 
)

Gets the index of the cell which contains a position in the map frame.

Parameters
[out]indexof the cell.
[in]positionthe position in the map frame.
[in]mapLengththe lengths in x and y direction.
[in]mapPositionthe position of the map.
[in]resolutionthe resolution of the map.
[in]bufferSizethe size of the buffer (optional).
[in]bufferStartIndexthe index of the starting point of the circular buffer (optional).
Returns
true if successful, false if position outside of map.

Definition at line 129 of file GridMapMath.cpp.

bool grid_map::getIndexShiftFromPositionShift ( Index indexShift,
const Vector positionShift,
const double &  resolution 
)

Computes how many cells/indeces the map is moved based on a position shift in the grid map frame. Use this function if you are moving the grid map and want to ensure that the cells match before and after.

Parameters
[out]indexShiftthe corresponding shift of the indices.
[in]positionShiftthe desired position shift.
[in]resolutionthe resolution of the map.
Returns
true if successful.

Definition at line 168 of file GridMapMath.cpp.

double grid_map::getLayerValue ( const Matrix layerMat,
int  rowReq,
int  colReq 
)

Extract the value of the specific layer at the row and column requested. If row and column are out of bounds they will be bound to range.

Parameters
[in]layerMat- matrix of the layer from where the data is extracted
[in]rowReq- row requested
[in]colReq- column requested
Returns
- value of the layer at rowReq and colReq

Definition at line 27 of file CubicInterpolation.cpp.

size_t grid_map::getLinearIndexFromIndex ( const Index index,
const Size bufferSize,
const bool  rowMajor = false 
)

Returns the linear index (1-dim.) corresponding to the regular index (2-dim.) for either row- or column-major format. Note: Eigen is defaulting to column-major format.

Parameters
[in]indexthe regular 2d index.
[in]bufferSizethe map buffer size.
[in](optional)rowMajor if the linear index is generated for row-major format.
Returns
the linear 1d index.

Definition at line 508 of file GridMapMath.cpp.

bool grid_map::getPositionFromIndex ( Position position,
const Index index,
const Length mapLength,
const Position mapPosition,
const double &  resolution,
const Size bufferSize,
const Index bufferStartIndex = Index::Zero() 
)

Gets the position of a cell specified by its index in the map frame.

Parameters
[out]positionthe position of the center of the cell in the map frame.
[in]indexof the cell.
[in]mapLengththe lengths in x and y direction.
[in]mapPositionthe position of the map.
[in]resolutionthe resolution of the map.
[in]bufferSizethe size of the buffer (optional).
[in]bufferStartIndexthe index of the starting point of the circular buffer (optional).
Returns
true if successful, false if index not within range of buffer.

Definition at line 114 of file GridMapMath.cpp.

void grid_map::getPositionOfDataStructureOrigin ( const Position position,
const Length mapLength,
Position positionOfOrigin 
)

Gets the position of the data structure origin.

Parameters
[in]positionthe position of the map.
[in]mapLengththe map length.
[out]positionOfOriginthe position of the data structure origin.

Definition at line 159 of file GridMapMath.cpp.

bool grid_map::getPositionShiftFromIndexShift ( Vector positionShift,
const Index indexShift,
const double &  resolution 
)

Computes the corresponding position shift from a index shift. Use this function if you are moving the grid map and want to ensure that the cells match before and after.

Parameters
[out]positionShiftthe corresponding shift in position in the grid map frame.
[in]indexShiftthe desired shift of the indeces.
[in]resolutionthe resolution of the map.
Returns
true if successful.

Definition at line 183 of file GridMapMath.cpp.

bool grid_map::getSubmapInformation ( Index submapTopLeftIndex,
Size submapBufferSize,
Position submapPosition,
Length submapLength,
Index requestedIndexInSubmap,
const Position requestedSubmapPosition,
const Length requestedSubmapLength,
const Length mapLength,
const Position mapPosition,
const double &  resolution,
const Size bufferSize,
const Index bufferStartIndex = Index::Zero() 
)

Given a map and a desired submap (defined by position and size), this function computes various information about the submap. The returned submap might be smaller than the requested size as it respects the boundaries of the map.

Parameters
[out]submapTopLeftIndexthe top left index of the returned submap.
[out]submapBufferSizethe buffer size of the returned submap.
[out]submapPositionthe position of the submap (center) in the map frame.
[out]submapLengththe length of the submap.
[out]requestedIndexInSubmapthe index in the submap that corresponds to the requested position of the submap.
[in]requestedSubmapPositionthe requested submap position (center) in the map frame.
[in]requestedSubmapLengththe requested submap length.
[in]mapLengththe lengths in x and y direction.
[in]mapPositionthe position of the map.
[in]resolutionthe resolution of the map.
[in]bufferSizethe buffer size of the map.
[in]bufferStartIndexthe index of the starting point of the circular buffer (optional).
Returns
true if successful.

Definition at line 271 of file GridMapMath.cpp.

Size grid_map::getSubmapSizeFromCornerIndeces ( const Index topLeftIndex,
const Index bottomRightIndex,
const Size bufferSize,
const Index bufferStartIndex 
)

Computes the buffer size of a submap given a top left and a lower right index.

Parameters
topLeftIndexthe top left index in the map.
bottomRightIndexthe bottom right index in the map.
Returns
buffer size for the submap.

Definition at line 321 of file GridMapMath.cpp.

bool grid_map::incrementIndex ( Index index,
const Size bufferSize,
const Index bufferStartIndex = Index::Zero() 
)

Increases the index by one to iterate through the map. Increments either to the neighboring index to the right or to the start of the lower row. Returns false if end of iterations are reached.

Parameters

Definition at line 437 of file GridMapMath.cpp.

bool grid_map::incrementIndexForSubmap ( Index submapIndex,
Index index,
const Index submapTopLeftIndex,
const Size submapBufferSize,
const Size bufferSize,
const Index bufferStartIndex = Index::Zero() 
)

Increases the index by one to iterate through the cells of a submap. Increments either to the neighboring index to the right or to the start of the lower row. Returns false if end of iterations are reached.

Note: This function does not check if submap actually fits to the map. This needs to be checked before separately.

Parameters

Definition at line 459 of file GridMapMath.cpp.

template<int N>
Eigen::Matrix<double,N,N> grid_map::randomCovariance ( )

Definition at line 18 of file gtest_eigen.hpp.

Eigen::MatrixXd grid_map::randomCovarianceXd ( int  N)
inline

Definition at line 25 of file gtest_eigen.hpp.

void grid_map::wrapIndexToRange ( Index index,
const Size bufferSize 
)

Wraps an index that runs out of the range of the buffer back into allowed the region. This means that an index that overflows is reset to zero. This is the 2d version of wrapIndexToRange(int&, const int&).

Parameters

Definition at line 213 of file GridMapMath.cpp.

void grid_map::wrapIndexToRange ( int &  index,
int  bufferSize 
)

Wraps an index that runs out of the range of the buffer back into allowed the region. This means that an index that overflows is reset to zero.

Parameters

Definition at line 220 of file GridMapMath.cpp.



grid_map_core
Author(s): Péter Fankhauser
autogenerated on Tue Jun 1 2021 02:13:27