|
void | assertEqual (const M1 &A, const M2 &B, std::string const &message="") |
|
void | assertFinite (const M1 &A, std::string const &="") |
|
void | assertNear (const M1 &A, const M2 &B, T tolerance, std::string const &message="") |
|
unsigned int | bindIndexToRange (unsigned 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=nullptr) |
|
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) |
|
Eigen::Matrix2i | getBufferOrderToMapFrameAlignment () |
|
bool | getBufferRegionsForSubmap (std::vector< BufferRegion > &submapBufferRegions, const Index &submapIndex, const Size &submapBufferSize, const Size &bufferSize, const Index &bufferStartIndex=Index::Zero()) |
|
template<typename MultiArrayMessageType_ > |
unsigned int | getCols (const MultiArrayMessageType_ &message) |
|
Index | getIndexFromBufferIndex (const Index &bufferIndex, const Size &bufferSize, const Index &bufferStartIndex) |
|
Index | getIndexFromLinearIndex (size_t linearIndex, const Size &bufferSize, 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, unsigned int rowReq, unsigned int colReq) |
|
double | getLayerValue (const Matrix &layerMat, int rowReq, int colReq) |
|
size_t | getLinearIndexFromIndex (const Index &index, const Size &bufferSize, 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) |
|
template<typename MultiArrayMessageType_ > |
unsigned int | getRows (const MultiArrayMessageType_ &message) |
|
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 | getSubmapSizeFromCornerIndices (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<typename MultiArrayMessageType_ > |
bool | isRowMajor (const MultiArrayMessageType_ &message) |
|
template<typename EigenType_ , typename MultiArrayMessageType_ > |
bool | matrixEigenCopyToMultiArrayMessage (const EigenType_ &e, MultiArrayMessageType_ &m) |
|
template<typename EigenType_ , typename MultiArrayMessageType_ > |
bool | multiArrayMessageCopyToMatrixEigen (const MultiArrayMessageType_ &m, EigenType_ &e) |
|
template<typename EigenType_ , typename MultiArrayMessageType_ > |
bool | multiArrayMessageMapToMatrixEigen (MultiArrayMessageType_ &m, EigenType_ &e) |
|
int | nDimensions () |
|
Eigen::Matrix< double, N, N > | randomCovariance () |
|
Eigen::MatrixXd | randomCovarianceXd (int N) |
|
| TEST (GridMap, ClipToMap) |
|
| TEST (IndexFromPosition, EdgeCases) |
|
| TEST (IndexFromPosition, CircularBuffer) |
|
| TEST (LineIterator, StartAndEndOutsideMapWithoutIntersectingMap) |
|
| TEST (GridMap, Transform) |
|
| TEST (getSubmapInformation, Zero) |
|
| TEST (getSubmapInformation, CircularBuffer) |
|
| TEST (LineIterator, StartAndEndOutsideMovedMap) |
|
| TEST (getSubmapInformation, Debug2) |
|
| TEST (PositionFromIndex, CircularBuffer) |
|
| TEST (checkIncrementIndexForSubmap, CircularBuffer) |
|
| TEST (GridMap, CopyAssign) |
|
| TEST (SubmapIterator, Simple) |
|
| TEST (PositionFromIndex, Simple) |
|
| TEST (LineIterator, StartOutsideMap) |
|
| TEST (GridMap, CopyConstructor) |
|
| TEST (getBufferRegionsForSubmap, Simple) |
|
| TEST (wrapIndexToRange, All) |
|
| TEST (GridMap, Move) |
|
| TEST (getPositionShiftFromIndexShift, All) |
|
| TEST (getSubmapInformation, Simple) |
|
| TEST (AddDataFrom, ExtendMapNotAligned) |
|
| TEST (checkIncrementIndexForSubmap, Simple) |
|
| TEST (checkIncrementIndex, CircularBuffer) |
|
| TEST (LineIterator, StartAndEndOutsideMap) |
|
| TEST (ValueAtPosition, LinearInterpolated) |
|
| TEST (ValueAtPosition, NearestNeighbor) |
|
| TEST (LineIterator, MovedMap) |
|
| TEST (checkIncrementIndex, Simple) |
|
| TEST (getIndexShiftFromPositionShift, All) |
|
| TEST (getSubmapInformation, ExceedingBoundaries) |
|
| TEST (LineIterator, EndOutsideMap) |
|
| TEST (IndexFromPosition, Simple) |
|
| TEST (getBufferRegionsForSubmap, CircularBuffer) |
|
| TEST (getBufferRegionsForSubmap, Trivial) |
|
| TEST (SubmapIterator, CircularBuffer) |
|
| TEST (getIndexFromLinearIndex, Simple) |
|
| TEST (boundPositionToRange, Simple) |
|
| TEST (AddDataFrom, CopyData) |
|
| TEST (boundIndexToRange, All) |
|
| TEST (boundPositionToRange, Position) |
|
| TEST (SubmapIterator, InterleavedExecutionWithMove) |
|
| TEST (getSubmapInformation, Debug1) |
|
| TEST (checkIfIndexInRange, All) |
|
| TEST (GridMap, ClipToMap2) |
|
| TEST (AddDataFrom, ExtendMapAligned) |
|
| TEST (checkIfPositionWithinMap, Outside) |
|
| TEST (checkIfPositionWithinMap, EdgeCases) |
|
| TEST (checkIfPositionWithinMap, Inside) |
|
void | wrapIndexToRange (int &index, int bufferSize) |
|
void | wrapIndexToRange (Index &index, const Size &bufferSize) |
|