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 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.
|
strong |
Enumerator | |
---|---|
INTER_NEAREST | |
INTER_LINEAR | |
INTER_CUBIC_CONVOLUTION | |
INTER_CUBIC |
Definition at line 39 of file TypeDefs.hpp.
void grid_map::assertEqual | ( | const M1 & | A, |
const M2 & | B, | ||
std::string const & | message = "" |
||
) |
Definition at line 33 of file gtest_eigen.hpp.
void grid_map::assertFinite | ( | const M1 & | A, |
std::string const & | message = "" |
||
) |
Definition at line 99 of file gtest_eigen.hpp.
void grid_map::assertNear | ( | const M1 & | A, |
const M2 & | B, | ||
T | 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.
[in] | idReq | - input index . |
[in] | nElem | - number of elements in the container |
Definition at line 16 of file CubicInterpolation.cpp.
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&).
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.
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.
Definition at line 241 of file GridMapMath.cpp.
Checks if index is within range of the buffer.
[in] | index | to check. |
[in] | bufferSize | the size 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.
[in] | position | the position which is to be checked. |
[in] | mapLength | the length of the map. |
[in] | mapPosition | the position of the map. |
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).
[in] | colorValue | the concatenated RGB color value. |
[out] | colorVector | the color vector in RGB from 0-255. |
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).
[in] | colorValue | the concatenated RGB color value. |
[out] | colorVector | the color vector in RGB from 0.0-1.0. |
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).
[in] | colorValue | the concatenated RGB color value. |
[out] | colorVector | the color vector in RGB from 0.0-1.0. |
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.
[in] | colorVector | the color vector in RGB from 0-255. |
[out] | colorValue | the concatenated RGB color value. |
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.
[in] | colorVector | the color vector in RGB from 0-255. |
[out] | colorValue | the 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.
[in] | colorVector | the color vector in RGB from 0.0-1.0. |
[out] | colorValue | the concatenated RGB color value. |
Definition at line 557 of file GridMapMath.cpp.
|
inline |
Definition at line 110 of file gtest_eigen.hpp.
void grid_map::expectNear | ( | const M1 & | A, |
const M2 & | B, | ||
T | 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).
index | the unwrapped index. |
bufferSize | the map buffer size. |
bufferStartIndex | the map buffer start 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).
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.
[out] | submapBufferRegions | the list of buffer regions that make up the submap. |
[in] | submapIndex | the index (top-left) for the requested submap. |
[in] | submapBufferSize | the size of the requested submap. |
[in] | bufferSize | the buffer size of the map. |
[in] | bufferStartIndex | the index of the starting point of the circular buffer (optional). |
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.
bufferIndex | the index in the circular buffer. |
bufferSize | the map buffer size. |
bufferStartIndex | the map buffer start 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.
[in] | linearIndex | the he linear 1d index. |
[in] | bufferSize | the map buffer size. |
[in] | (optional) | rowMajor if the linear index is generated for row-major format. |
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.
[out] | index | of the cell. |
[in] | position | the position in the map frame. |
[in] | mapLength | the lengths in x and y direction. |
[in] | mapPosition | the position of the map. |
[in] | resolution | the resolution of the map. |
[in] | bufferSize | the size of the buffer (optional). |
[in] | bufferStartIndex | the index of the starting point of the circular buffer (optional). |
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.
[out] | indexShift | the corresponding shift of the indices. |
[in] | positionShift | the desired position shift. |
[in] | resolution | the resolution of the map. |
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.
[in] | layerMat | - matrix of the layer from where the data is extracted |
[in] | rowReq | - row requested |
[in] | colReq | - column requested |
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.
[in] | index | the regular 2d index. |
[in] | bufferSize | the map buffer size. |
[in] | (optional) | rowMajor if the linear index is generated for row-major format. |
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.
[out] | position | the position of the center of the cell in the map frame. |
[in] | index | of the cell. |
[in] | mapLength | the lengths in x and y direction. |
[in] | mapPosition | the position of the map. |
[in] | resolution | the resolution of the map. |
[in] | bufferSize | the size of the buffer (optional). |
[in] | bufferStartIndex | the index of the starting point of the circular buffer (optional). |
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.
[in] | position | the position of the map. |
[in] | mapLength | the map length. |
[out] | positionOfOrigin | the 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.
[out] | positionShift | the corresponding shift in position in the grid map frame. |
[in] | indexShift | the desired shift of the indeces. |
[in] | resolution | the resolution of the map. |
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.
[out] | submapTopLeftIndex | the top left index of the returned submap. |
[out] | submapBufferSize | the buffer size of the returned submap. |
[out] | submapPosition | the position of the submap (center) in the map frame. |
[out] | submapLength | the length of the submap. |
[out] | requestedIndexInSubmap | the index in the submap that corresponds to the requested position of the submap. |
[in] | requestedSubmapPosition | the requested submap position (center) in the map frame. |
[in] | requestedSubmapLength | the requested submap length. |
[in] | mapLength | the lengths in x and y direction. |
[in] | mapPosition | the position of the map. |
[in] | resolution | the resolution of the map. |
[in] | bufferSize | the buffer size of the map. |
[in] | bufferStartIndex | the index of the starting point of the circular buffer (optional). |
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.
topLeftIndex | the top left index in the map. |
bottomRightIndex | the bottom right index in the map. |
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.
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.
Definition at line 459 of file GridMapMath.cpp.
Eigen::Matrix<double,N,N> grid_map::randomCovariance | ( | ) |
Definition at line 18 of file gtest_eigen.hpp.
|
inline |
Definition at line 25 of file gtest_eigen.hpp.
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&).
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.
Definition at line 220 of file GridMapMath.cpp.