Classes | Typedefs | Functions
grid_map_visualization Namespace Reference

Classes

class  FlatPointCloudVisualization
class  GridCellsVisualization
class  GridMapVisualization
class  MapRegionVisualization
class  OccupancyGridVisualization
class  PointCloudVisualization
class  VectorVisualization
class  VisualizationBase
class  VisualizationFactory

Typedefs

typedef std::map< std::string,
XmlRpc::XmlRpcValue > 
StringMap

Functions

double computeLinearMapping (const double &sourceValue, const double &sourceLowerValue, const double &sourceUpperValue, const double &mapLowerValue, const double &mapUpperValue)
void getColorMessageFromColorVector (std_msgs::ColorRGBA &colorMessage, const Eigen::Vector3f &colorVector, bool resetTransparency=true)
void getColorVectorFromColorMessage (Eigen::Vector3f &colorVector, const std_msgs::ColorRGBA &colorMessage)
void interpolateBetweenColors (std_msgs::ColorRGBA &color, const std_msgs::ColorRGBA &colorForLowerValue, const std_msgs::ColorRGBA &colorForUpperValue, const double value, const double lowerValueBound, const double upperValueBound)
void setColorChannelFromValue (float &colorChannel, const double value, const double lowerValueBound, const double upperValueBound, const bool invert=false, const double colorChannelLowerValue=0.0, const double colorChannelUpperValue=1.0)
void setColorFromColorValue (std_msgs::ColorRGBA &color, const unsigned long &colorValue, bool resetTransparency=true)
void setColorFromValue (std_msgs::ColorRGBA &color, const double value, const double lowerValueBound, const double upperValueBound)
void setSaturationFromValue (std_msgs::ColorRGBA &color, const double value, const double lowerValueBound, const double upperValueBound, const double maxSaturation, const double minSaturation)

Typedef Documentation

typedef std::map<std::string, XmlRpc::XmlRpcValue> grid_map_visualization::StringMap

Definition at line 18 of file VisualizationBase.hpp.


Function Documentation

double grid_map_visualization::computeLinearMapping ( const double &  sourceValue,
const double &  sourceLowerValue,
const double &  sourceUpperValue,
const double &  mapLowerValue,
const double &  mapUpperValue 
)

Computes a linear mapping for a query from the source and to the map.

Parameters:
sourceValuethe query from the source.
sourceLowerValuethe lower source boundary.
sourceUpperValuethe upper source boundary.
mapLowerValuethe lower map boundary.
mapUpperValuethe upper map boundary.
Returns:
the query mapped to the map.

Definition at line 96 of file GridMapVisualizationHelpers.cpp.

void grid_map_visualization::getColorMessageFromColorVector ( std_msgs::ColorRGBA &  colorMessage,
const Eigen::Vector3f &  colorVector,
bool  resetTransparency = true 
)

Create a color message from a color vector.

Parameters:
[out]colorMessagethe color message.
[in]colorVectorthe color vector
[in]resetTransparencyif transparency should be reset (to fully visible) or left at current value.

Definition at line 18 of file GridMapVisualizationHelpers.cpp.

void grid_map_visualization::getColorVectorFromColorMessage ( Eigen::Vector3f &  colorVector,
const std_msgs::ColorRGBA &  colorMessage 
)

Create a color vector from a color message.

Parameters:
[out]colorVectorthe color vector.
[in]colorMessagethe color message.

Definition at line 26 of file GridMapVisualizationHelpers.cpp.

void grid_map_visualization::interpolateBetweenColors ( std_msgs::ColorRGBA &  color,
const std_msgs::ColorRGBA &  colorForLowerValue,
const std_msgs::ColorRGBA &  colorForUpperValue,
const double  value,
const double  lowerValueBound,
const double  upperValueBound 
)

Sets the color to the interpolation between two colors based on a scalar value.

Parameters:
[out]colorthe color the be set.
[in]colorForLowerValuethe color for the lower value boundary.
[in]colorForUpperValuethe color for the upper value boundary.
[in]valuethe scalar value.
[in]lowerValueBoundthe lower boundary of the value.
[in]upperValueBoundthe upper boundary of the value.

Definition at line 54 of file GridMapVisualizationHelpers.cpp.

void grid_map_visualization::setColorChannelFromValue ( float &  colorChannel,
const double  value,
const double  lowerValueBound,
const double  upperValueBound,
const bool  invert = false,
const double  colorChannelLowerValue = 0.0,
const double  colorChannelUpperValue = 1.0 
)

Set the color channel from a scalar value.

Parameters:
[out]colorChannelthe color channel to be set.
[in]valuethe scalar value.
[in]lowerValueBoundthe lower boundary of the value.
[in]upperValueBoundthe upper boundary of the value.
[in]invertif interpolation should be inverted.
[in]colorChannelLowerValuethe lower value for the color channel.
[in]colorChannelUpperValuethe upper value for the color channel.

Definition at line 38 of file GridMapVisualizationHelpers.cpp.

void grid_map_visualization::setColorFromColorValue ( std_msgs::ColorRGBA &  color,
const unsigned long &  colorValue,
bool  resetTransparency = true 
)

Sets a color message from a color value.

Parameters:
[out]colorthe color message.
[in]colorValuethe color value.
[in]resetTransparencyif transparency should be reset (to fully visible) or left at current value.

Definition at line 31 of file GridMapVisualizationHelpers.cpp.

void grid_map_visualization::setColorFromValue ( std_msgs::ColorRGBA &  color,
const double  value,
const double  lowerValueBound,
const double  upperValueBound 
)

Set the color from the rainbow color spectrum based on scalar value.

Parameters:
[out]colorthe color the be set.
[in]valuethe scalar value.
[in]lowerValueBoundthe lower boundary of the value.
[in]upperValueBoundthe upper boundary of the value.

Definition at line 77 of file GridMapVisualizationHelpers.cpp.

void grid_map_visualization::setSaturationFromValue ( std_msgs::ColorRGBA &  color,
const double  value,
const double  lowerValueBound,
const double  upperValueBound,
const double  maxSaturation,
const double  minSaturation 
)

Sets the saturation of the color from a scalar value.

Parameters:
[out]colorthe color the be set.
[in]valuethe scalar value.
[in]lowerValueBoundthe lower boundary of the value.
[in]upperValueBoundthe upper boundary of the value.
[in]maxSaturationthe maximum saturation.
[in]minSaturationthe minimum saturation.

Definition at line 63 of file GridMapVisualizationHelpers.cpp.



grid_map_visualization
Author(s): Péter Fankhauser
autogenerated on Mon Oct 9 2017 03:09:35