#include <GridCellsVisualization.hpp>
Public Member Functions | |
GridCellsVisualization (ros::NodeHandle &nodeHandle, const std::string &name) | |
bool | initialize () |
bool | readParameters (XmlRpc::XmlRpcValue &config) |
bool | visualize (const grid_map::GridMap &map) |
virtual | ~GridCellsVisualization () |
Private Attributes | |
std::string | layer_ |
Type that is transformed to the occupancy grid. | |
float | lowerThreshold_ |
Values that are between lower and upper threshold are shown. | |
float | upperThreshold_ |
Definition at line 19 of file GridCellsVisualization.hpp.
grid_map_visualization::GridCellsVisualization::GridCellsVisualization | ( | ros::NodeHandle & | nodeHandle, |
const std::string & | name | ||
) |
Constructor.
nodeHandle | the ROS node handle. |
name | the name of the visualization. |
Definition at line 18 of file GridCellsVisualization.cpp.
Destructor.
Definition at line 25 of file GridCellsVisualization.cpp.
bool grid_map_visualization::GridCellsVisualization::initialize | ( | ) | [virtual] |
Initialization.
Implements grid_map_visualization::VisualizationBase.
Definition at line 49 of file GridCellsVisualization.cpp.
bool grid_map_visualization::GridCellsVisualization::readParameters | ( | XmlRpc::XmlRpcValue & | config | ) | [virtual] |
Read parameters from ROS.
config | the parameters as XML. |
Reimplemented from grid_map_visualization::VisualizationBase.
Definition at line 29 of file GridCellsVisualization.cpp.
bool grid_map_visualization::GridCellsVisualization::visualize | ( | const grid_map::GridMap & | map | ) | [virtual] |
Generates the visualization.
map | the grid map to visualize. |
Implements grid_map_visualization::VisualizationBase.
Definition at line 55 of file GridCellsVisualization.cpp.
std::string grid_map_visualization::GridCellsVisualization::layer_ [private] |
Type that is transformed to the occupancy grid.
Definition at line 57 of file GridCellsVisualization.hpp.
float grid_map_visualization::GridCellsVisualization::lowerThreshold_ [private] |
Values that are between lower and upper threshold are shown.
Definition at line 60 of file GridCellsVisualization.hpp.
float grid_map_visualization::GridCellsVisualization::upperThreshold_ [private] |
Definition at line 60 of file GridCellsVisualization.hpp.