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

Namespaces

 bicubic
 
 bicubic_conv
 
 internal
 

Classes

class  BufferRegion
 
class  CircleIterator
 
struct  Clamp
 
union  Color
 
class  EllipseIterator
 
class  GridMap
 
class  GridMapCvConverter
 
class  GridMapCvProcessing
 
class  GridMapIterator
 
class  GridMapRosConverter
 
class  InpaintFilter
 
class  LineIterator
 
class  Polygon
 
class  PolygonIterator
 
class  PolygonRosConverter
 
class  SlidingWindowIterator
 
class  SpiralIterator
 
class  SubmapGeometry
 
class  SubmapIterator
 

Typedefs

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

Enumerations

enum  InterpolationMethods { InterpolationMethods::INTER_NEAREST, InterpolationMethods::INTER_LINEAR, InterpolationMethods::INTER_CUBIC_CONVOLUTION, InterpolationMethods::INTER_CUBIC }
 
enum  InterpolationMethods { InterpolationMethods::INTER_NEAREST, InterpolationMethods::INTER_LINEAR, InterpolationMethods::INTER_CUBIC_CONVOLUTION, InterpolationMethods::INTER_CUBIC }
 
enum  StorageIndices { StorageIndices::Column, StorageIndices::Row }
 

Functions

void assertEqual (const M1 &A, const M2 &B, std::string const &message="")
 
void assertFinite (const M1 &A, std::string const &message="")
 
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)
 
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())
 
template<typename MultiArrayMessageType_ >
unsigned int getCols (const MultiArrayMessageType_ &message)
 
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)
 
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 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<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)
 
void wrapIndexToRange (int &index, int bufferSize)
 
void wrapIndexToRange (Index &index, const Size &bufferSize)
 

Variables

std::map< StorageIndices, std::string > storageIndexNames
 Holds the names of the storage indeces. More...
 

Enumeration Type Documentation

Enumerator
Column 
Row 

Definition at line 28 of file GridMapMsgHelpers.hpp.

Function Documentation

template<typename MultiArrayMessageType_ >
unsigned int grid_map::getCols ( const MultiArrayMessageType_ &  message)

Returns the number of columns of the message data.

Template Parameters
MultiArrayMessageType_a std_msgs::xxxMultiArray message (e.g. std_msgs::Float32MultiArray).
Parameters
[in]messagethe message data.
Returns
the number of columns.

Definition at line 58 of file GridMapMsgHelpers.hpp.

template<typename MultiArrayMessageType_ >
unsigned int grid_map::getRows ( const MultiArrayMessageType_ &  message)

Returns the number of rows of the message data.

Template Parameters
MultiArrayMessageType_a std_msgs::xxxMultiArray message (e.g. std_msgs::Float32MultiArray).
Parameters
[in]messagethe message data.
Returns
the number of rows.

Definition at line 71 of file GridMapMsgHelpers.hpp.

template<typename MultiArrayMessageType_ >
bool grid_map::isRowMajor ( const MultiArrayMessageType_ &  message)

Checks if message data is stored in row-major format.

Template Parameters
MultiArrayMessageType_a std_msgs::xxxMultiArray message (e.g. std_msgs::Float32MultiArray).
Parameters
[in]messagethe message data.
Returns
true if is in row-major format, false if is in column-major format.

Definition at line 43 of file GridMapMsgHelpers.hpp.

template<typename EigenType_ , typename MultiArrayMessageType_ >
bool grid_map::matrixEigenCopyToMultiArrayMessage ( const EigenType_ &  e,
MultiArrayMessageType_ &  m 
)

Copies an Eigen matrix into a ROS MultiArray message. Both column- and row-major matrices are allowed, and the type will be marked in the layout labels.

Template Parameters
MultiArrayMessageType_a std_msgs::xxxMultiArray message (e.g. std_msgs::Float32MultiArray).
EigenType_an Eigen matrix with matching Scalar type as that of the multi-array message.
Parameters
[in]ethe Eigen matrix to be converted.
[out]mthe ROS message to which the data will be copied.
Returns
true if successful.

Definition at line 88 of file GridMapMsgHelpers.hpp.

template<typename EigenType_ , typename MultiArrayMessageType_ >
bool grid_map::multiArrayMessageCopyToMatrixEigen ( const MultiArrayMessageType_ &  m,
EigenType_ &  e 
)

Copies a ROS xxxMultiArray message into an Eigen matrix.

Template Parameters
MultiArrayMessageType_a std_msgs::xxxMultiArray message (e.g. std_msgs::Float32MultiArray)
EigenType_an Eigen matrix with matching Scalar type as that of the multi-array message.
Parameters
[in]mthe ROS message to which the data will be copied.
[out]ethe Eigen matrix to be converted.
Returns
true if successful.

Definition at line 117 of file GridMapMsgHelpers.hpp.

template<typename EigenType_ , typename MultiArrayMessageType_ >
bool grid_map::multiArrayMessageMapToMatrixEigen ( MultiArrayMessageType_ &  m,
EigenType_ &  e 
)

Maps a ROS xxxMultiArray message into an Eigen matrix. Both column- and row-major message types are allowed.

Parameters
[in]mthe ROS message to be converted.
[out]ethe Eigen matrix to which the data will be mapped.
Returns
true if successful.

Definition at line 138 of file GridMapMsgHelpers.hpp.

int grid_map::nDimensions ( )

Returns the number of dimensions of the grid map.

Returns
number of dimensions.

Definition at line 16 of file GridMapMsgHelpers.cpp.

Variable Documentation

std::map< StorageIndices, std::string > grid_map::storageIndexNames
Initial value:
= boost::assign::map_list_of
(StorageIndices::Column, "column_index")
(StorageIndices::Row, "row_index")

Holds the names of the storage indeces.

Definition at line 21 of file GridMapMsgHelpers.cpp.



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