Public Types | Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | Static Private Attributes | List of all members
grid_map_rviz_plugin::GridMapVisual Class Reference

#include <GridMapVisual.hpp>

Public Types

using ColorArray = Eigen::Array< Ogre::ColourValue, Eigen::Dynamic, Eigen::Dynamic >
 
using MaskArray = Eigen::Array< bool, Eigen::Dynamic, Eigen::Dynamic >
 
using MatrixConstRef = Eigen::Ref< const grid_map::Matrix >
 

Public Member Functions

void computeVisualization (float alpha, bool showGridLines, bool flatTerrain, std::string heightLayer, bool flatColor, bool noColor, Ogre::ColourValue meshColor, bool mapLayerColor, std::string colorLayer, std::string colorMap, bool useColorMap, bool invertColorMap, Ogre::ColourValue minColor, Ogre::ColourValue maxColor, bool autocomputeIntensity, float minIntensity, float maxIntensity, float gridLineThickness, int gridCellDecimation)
 
std::vector< std::string > getLayerNames ()
 
 GridMapVisual (Ogre::SceneManager *sceneManager, Ogre::SceneNode *parentNode)
 
void setFrameOrientation (const Ogre::Quaternion &orientation)
 
void setFramePosition (const Ogre::Vector3 &position)
 
void setMessage (const grid_map_msgs::GridMap::ConstPtr &msg)
 
virtual ~GridMapVisual ()
 

Private Types

enum  ColoringMethod {
  ColoringMethod::FLAT, ColoringMethod::COLOR_LAYER, ColoringMethod::INTENSITY_LAYER_MANUAL, ColoringMethod::INTENSITY_LAYER_COLORMAP,
  ColoringMethod::INTENSITY_LAYER_INVERTED_COLORMAP
}
 

Private Member Functions

ColorArray computeColorValues (MatrixConstRef heightData, MatrixConstRef colorData, ColoringMethod coloringMethod, std::string colorMap, Ogre::ColourValue flatColor, double minIntensity, double maxIntensity, bool autocomputeIntensity, Ogre::ColourValue minColor, Ogre::ColourValue maxColor)
 
MaskArray computeIsValidMask (std::vector< std::string > basicLayers)
 
std::vector< Ogre::Vector3computeMeshLineVertices (int i, int j, int gridCellDecimation, bool isNthRow, bool isNthCol, bool isLastRow, bool isLastCol, double resolution, const grid_map::Position &topLeft, const Eigen::ArrayXXf &heightOrFlatData, const MaskArray &isValid) const
 
Ogre::ColourValue getInterpolatedColor (float intensity, Ogre::ColourValue minColor, Ogre::ColourValue maxColor)
 
void initializeAndBeginManualObject (size_t nVertices)
 
void initializeMeshLines (size_t cols, size_t rows, double resolution, double alpha, double lineWidth)
 
void printMissingBasicLayers (const std::vector< std::string > &basicLayers) const
 Logs a warning message which lists the basic layers that are missing from the grid map. More...
 

Static Private Member Functions

static Ogre::ColourValue getRainbowColor (float intensity)
 
static void normalizeIntensity (float &intensity, float minIntensity, float maxIntensity)
 

Private Attributes

Ogre::SceneNode * frameNode_
 
bool haveMap_
 
Ogre::ManualObject * manualObject_
 
grid_map::GridMap map_
 
Ogre::MaterialPtr material_
 
std::string materialName_
 
boost::shared_ptr< rviz::BillboardLinemeshLines_
 
Ogre::SceneManager * sceneManager_
 

Static Private Attributes

static constexpr double warningMessageThrottlePeriod_ {10.0}
 

Detailed Description

Definition at line 31 of file GridMapVisual.hpp.

Member Typedef Documentation

◆ ColorArray

using grid_map_rviz_plugin::GridMapVisual::ColorArray = Eigen::Array<Ogre::ColourValue, Eigen::Dynamic, Eigen::Dynamic>

Definition at line 34 of file GridMapVisual.hpp.

◆ MaskArray

using grid_map_rviz_plugin::GridMapVisual::MaskArray = Eigen::Array<bool, Eigen::Dynamic, Eigen::Dynamic>

Definition at line 33 of file GridMapVisual.hpp.

◆ MatrixConstRef

Definition at line 35 of file GridMapVisual.hpp.

Member Enumeration Documentation

◆ ColoringMethod

Enumerator
FLAT 
COLOR_LAYER 
INTENSITY_LAYER_MANUAL 
INTENSITY_LAYER_COLORMAP 
INTENSITY_LAYER_INVERTED_COLORMAP 

Definition at line 57 of file GridMapVisual.hpp.

Constructor & Destructor Documentation

◆ GridMapVisual()

grid_map_rviz_plugin::GridMapVisual::GridMapVisual ( Ogre::SceneManager *  sceneManager,
Ogre::SceneNode *  parentNode 
)

Definition at line 32 of file GridMapVisual.cpp.

◆ ~GridMapVisual()

grid_map_rviz_plugin::GridMapVisual::~GridMapVisual ( )
virtual

Definition at line 40 of file GridMapVisual.cpp.

Member Function Documentation

◆ computeColorValues()

GridMapVisual::ColorArray grid_map_rviz_plugin::GridMapVisual::computeColorValues ( GridMapVisual::MatrixConstRef  heightData,
GridMapVisual::MatrixConstRef  colorData,
GridMapVisual::ColoringMethod  coloringMethod,
std::string  colorMap,
Ogre::ColourValue  flatColor,
double  minIntensity,
double  maxIntensity,
bool  autocomputeIntensity,
Ogre::ColourValue  minColor,
Ogre::ColourValue  maxColor 
)
private

Computes a matrix of color values corresponding to the grid cells. Color is computed depending on the coloringMethod.

Parameters
heightDataHeight values of the cells.
colorDataValues of the layer specified for coloring the mesh.
coloringMethodThe strategy to color, see ColoringMethod.
colorMapcolorMap selected (string). See GridMapColorMaps.hpp
flatColorUsed only if coloringMethod is FLAT
minIntensityUsed for the intensity based coloring methods only.
maxIntensityUsed for the intensity based coloring methods only.
autocomputeIntensityWheter to override the values in min and max intensity and compute them based on the provided intensity data.
minColorUsed only if coloringMethod is COLOR_LAYER.
maxColorUsed only if coloringMethod is COLOR_LAYER.
Returns
The color for each cell.

Definition at line 302 of file GridMapVisual.cpp.

◆ computeIsValidMask()

GridMapVisual::MaskArray grid_map_rviz_plugin::GridMapVisual::computeIsValidMask ( std::vector< std::string >  basicLayers)
private

Computes a mask where all the provided basicLayers are finite. Used to do fast lockups during mesh creation.

Parameters
basicLayersThe values to check, if they are finite.
Returns
A boolean mask. True indicates that all layers are finite, false indicates that at least one layer is NAN.

Definition at line 357 of file GridMapVisual.cpp.

◆ computeMeshLineVertices()

std::vector< Ogre::Vector3 > grid_map_rviz_plugin::GridMapVisual::computeMeshLineVertices ( int  i,
int  j,
int  gridCellDecimation,
bool  isNthRow,
bool  isNthCol,
bool  isLastRow,
bool  isLastCol,
double  resolution,
const grid_map::Position topLeft,
const Eigen::ArrayXXf &  heightOrFlatData,
const MaskArray isValid 
) const
private

Returns a vector of ogre coordinates. Each coordinate is a vertex for a mesh line.

Parameters
iIndex of the current point in x.
jIndex of the current point in y.
gridCellDecimationInteger that defines how many cells to skip between mesh lines. E.g. if n=3, every third mesh line will be displayed.
isNthRowFlag to indicate the n-th row, where n = gridCellDecimation.
isNthColFlag to indicate the n-th column, where n = gridCellDecimation.
isLastRowFlag to indicate the last row.
isLastColFlag to indicate the last column.
resolutionThe resolution.
topLeftThe (x,y) position of the top left corner in the map.
heightOrFlatDataThe height data for the elevation (z coordinates).
isValidMask of indices with valid data (i.e. not nan or inf)
Returns

Definition at line 257 of file GridMapVisual.cpp.

◆ computeVisualization()

void grid_map_rviz_plugin::GridMapVisual::computeVisualization ( float  alpha,
bool  showGridLines,
bool  flatTerrain,
std::string  heightLayer,
bool  flatColor,
bool  noColor,
Ogre::ColourValue  meshColor,
bool  mapLayerColor,
std::string  colorLayer,
std::string  colorMap,
bool  useColorMap,
bool  invertColorMap,
Ogre::ColourValue  minColor,
Ogre::ColourValue  maxColor,
bool  autocomputeIntensity,
float  minIntensity,
float  maxIntensity,
float  gridLineThickness,
int  gridCellDecimation 
)

Definition at line 58 of file GridMapVisual.cpp.

◆ getInterpolatedColor()

Ogre::ColourValue grid_map_rviz_plugin::GridMapVisual::getInterpolatedColor ( float  intensity,
Ogre::ColourValue  minColor,
Ogre::ColourValue  maxColor 
)
private

Returns a linearly interpolated color between min and max Color with the weighting [0,1] specified by intensity.

Parameters
intensityThe weighting for interpolation, 0 means minColor, 1 means maxColor.
minColorThe lower color for interpolation.
maxColorThe upper color for interpolation.
Returns

Definition at line 424 of file GridMapVisual.cpp.

◆ getLayerNames()

std::vector< std::string > grid_map_rviz_plugin::GridMapVisual::getLayerNames ( )

Definition at line 388 of file GridMapVisual.cpp.

◆ getRainbowColor()

Ogre::ColourValue grid_map_rviz_plugin::GridMapVisual::getRainbowColor ( float  intensity)
staticprivate

Copied from rviz/src/rviz/default_plugin/point_cloud_transformers.cpp. Transforms an intensity value in [0,1] range to a rainbow coloring.

Parameters
intensityValue to color, should be in [0,1] range, otherwise it is clipped.
Returns
The corresponding rainbow color.

Definition at line 398 of file GridMapVisual.cpp.

◆ initializeAndBeginManualObject()

void grid_map_rviz_plugin::GridMapVisual::initializeAndBeginManualObject ( size_t  nVertices)
private

Initialized the manualObject if not already initialized and clears all previously added data.

Parameters
nVerticesAn estimate on the number of vertices to be added.

Definition at line 280 of file GridMapVisual.cpp.

◆ initializeMeshLines()

void grid_map_rviz_plugin::GridMapVisual::initializeMeshLines ( size_t  cols,
size_t  rows,
double  resolution,
double  alpha,
double  lineWidth 
)
private

Initialized the meshLines_ object. Should be called before adding lines. Sets the drawing style and allocates the buffer.

Parameters
colsNumber of columns that will be drawn.
rowsNumber of rows that will be drawn.
resolutionResolution of the map. Used to compute the line thickness.
alphaLine opacity.
lineWidthline thickness for the mesh lines

Definition at line 348 of file GridMapVisual.cpp.

◆ normalizeIntensity()

void grid_map_rviz_plugin::GridMapVisual::normalizeIntensity ( float &  intensity,
float  minIntensity,
float  maxIntensity 
)
staticprivate

Transforms the intensity into [0,1] range where 0 corresponds to the minIntensity and 1 to maxIntensity. The given value is clipped to that range.

Parameters
intensityThe intensity value to normalize.
minIntensityLower bound.
maxIntensityUpper bound.

Definition at line 392 of file GridMapVisual.cpp.

◆ printMissingBasicLayers()

void grid_map_rviz_plugin::GridMapVisual::printMissingBasicLayers ( const std::vector< std::string > &  basicLayers) const
private

Logs a warning message which lists the basic layers that are missing from the grid map.

Parameters
basicLayersBasic layers.

Definition at line 367 of file GridMapVisual.cpp.

◆ setFrameOrientation()

void grid_map_rviz_plugin::GridMapVisual::setFrameOrientation ( const Ogre::Quaternion &  orientation)

Definition at line 384 of file GridMapVisual.cpp.

◆ setFramePosition()

void grid_map_rviz_plugin::GridMapVisual::setFramePosition ( const Ogre::Vector3 position)

Definition at line 380 of file GridMapVisual.cpp.

◆ setMessage()

void grid_map_rviz_plugin::GridMapVisual::setMessage ( const grid_map_msgs::GridMap::ConstPtr &  msg)

Definition at line 52 of file GridMapVisual.cpp.

Member Data Documentation

◆ frameNode_

Ogre::SceneNode* grid_map_rviz_plugin::GridMapVisual::frameNode_
private

Definition at line 59 of file GridMapVisual.hpp.

◆ haveMap_

bool grid_map_rviz_plugin::GridMapVisual::haveMap_
private

Definition at line 74 of file GridMapVisual.hpp.

◆ manualObject_

Ogre::ManualObject* grid_map_rviz_plugin::GridMapVisual::manualObject_
private

Definition at line 63 of file GridMapVisual.hpp.

◆ map_

grid_map::GridMap grid_map_rviz_plugin::GridMapVisual::map_
private

Definition at line 71 of file GridMapVisual.hpp.

◆ material_

Ogre::MaterialPtr grid_map_rviz_plugin::GridMapVisual::material_
private

Definition at line 64 of file GridMapVisual.hpp.

◆ materialName_

std::string grid_map_rviz_plugin::GridMapVisual::materialName_
private

Definition at line 65 of file GridMapVisual.hpp.

◆ meshLines_

boost::shared_ptr<rviz::BillboardLine> grid_map_rviz_plugin::GridMapVisual::meshLines_
private

Definition at line 68 of file GridMapVisual.hpp.

◆ sceneManager_

Ogre::SceneManager* grid_map_rviz_plugin::GridMapVisual::sceneManager_
private

Definition at line 60 of file GridMapVisual.hpp.

◆ warningMessageThrottlePeriod_

constexpr double grid_map_rviz_plugin::GridMapVisual::warningMessageThrottlePeriod_ {10.0}
staticprivate

Definition at line 77 of file GridMapVisual.hpp.


The documentation for this class was generated from the following files:


grid_map_rviz_plugin
Author(s): Philipp Krüsi , Péter Fankhauser
autogenerated on Wed Jul 5 2023 02:23:55