Public Types | Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | 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 >
 

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, bool useRainbow, bool invertRainbow, Ogre::ColourValue minColor, Ogre::ColourValue maxColor, bool autocomputeIntensity, float minIntensity, float maxIntensity)
 
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_RAINBOW,
  ColoringMethod::INTENSITY_LAYER_INVERTED_RAINBOW
}
 

Private Member Functions

ColorArray computeColorValues (Eigen::Ref< const grid_map::Matrix > heightData, Eigen::Ref< const grid_map::Matrix > colorData, GridMapVisual::ColoringMethod coloringMethod, Ogre::ColourValue flatColor, double minIntensity, double maxIntensity, bool autocomputeIntensity, Ogre::ColourValue minColor, Ogre::ColourValue maxColor)
 
MaskArray computeIsValidMask (std::vector< std::string > basicLayers)
 
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)
 

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_
 

Detailed Description

Definition at line 31 of file GridMapVisual.hpp.

Member Typedef Documentation

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

Definition at line 34 of file GridMapVisual.hpp.

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

Definition at line 33 of file GridMapVisual.hpp.

Member Enumeration Documentation

Enumerator
FLAT 
COLOR_LAYER 
INTENSITY_LAYER_MANUAL 
INTENSITY_LAYER_RAINBOW 
INTENSITY_LAYER_INVERTED_RAINBOW 

Definition at line 56 of file GridMapVisual.hpp.

Constructor & Destructor Documentation

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

Definition at line 27 of file GridMapVisual.cpp.

grid_map_rviz_plugin::GridMapVisual::~GridMapVisual ( )
virtual

Definition at line 35 of file GridMapVisual.cpp.

Member Function Documentation

GridMapVisual::ColorArray grid_map_rviz_plugin::GridMapVisual::computeColorValues ( Eigen::Ref< const grid_map::Matrix heightData,
Eigen::Ref< const grid_map::Matrix colorData,
GridMapVisual::ColoringMethod  coloringMethod,
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.
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 255 of file GridMapVisual.cpp.

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 308 of file GridMapVisual.cpp.

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,
bool  useRainbow,
bool  invertRainbow,
Ogre::ColourValue  minColor,
Ogre::ColourValue  maxColor,
bool  autocomputeIntensity,
float  minIntensity,
float  maxIntensity 
)

Definition at line 51 of file GridMapVisual.cpp.

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 360 of file GridMapVisual.cpp.

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

Definition at line 324 of file GridMapVisual.cpp.

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 334 of file GridMapVisual.cpp.

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 233 of file GridMapVisual.cpp.

void grid_map_rviz_plugin::GridMapVisual::initializeMeshLines ( size_t  cols,
size_t  rows,
double  resolution,
double  alpha 
)
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.

Definition at line 299 of file GridMapVisual.cpp.

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 328 of file GridMapVisual.cpp.

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

Definition at line 320 of file GridMapVisual.cpp.

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

Definition at line 316 of file GridMapVisual.cpp.

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

Definition at line 45 of file GridMapVisual.cpp.

Member Data Documentation

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

Definition at line 58 of file GridMapVisual.hpp.

bool grid_map_rviz_plugin::GridMapVisual::haveMap_
private

Definition at line 73 of file GridMapVisual.hpp.

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

Definition at line 62 of file GridMapVisual.hpp.

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

Definition at line 70 of file GridMapVisual.hpp.

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

Definition at line 63 of file GridMapVisual.hpp.

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

Definition at line 64 of file GridMapVisual.hpp.

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

Definition at line 67 of file GridMapVisual.hpp.

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

Definition at line 59 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 Tue Jun 1 2021 02:13:47