#include <OccupancyGridVisualization.hpp>

Public Member Functions | |
| bool | initialize () |
| OccupancyGridVisualization (ros::NodeHandle &nodeHandle, const std::string &name) | |
| bool | readParameters (XmlRpc::XmlRpcValue &config) |
| bool | visualize (const grid_map::GridMap &map) |
| virtual | ~OccupancyGridVisualization () |
Private Attributes | |
| float | dataMax_ |
| float | dataMin_ |
| Minimum and maximum value of the grid map data (used to normalize the cell data in [min, max]). | |
| std::string | layer_ |
| Type that is transformed to the occupancy grid. | |
Definition at line 19 of file OccupancyGridVisualization.hpp.
| grid_map_visualization::OccupancyGridVisualization::OccupancyGridVisualization | ( | ros::NodeHandle & | nodeHandle, |
| const std::string & | name | ||
| ) |
Constructor.
| nodeHandle | the ROS node handle. |
| name | the name of the visualization. |
Definition at line 15 of file OccupancyGridVisualization.cpp.
Destructor.
Definition at line 22 of file OccupancyGridVisualization.cpp.
| bool grid_map_visualization::OccupancyGridVisualization::initialize | ( | ) | [virtual] |
Initialization.
Implements grid_map_visualization::VisualizationBase.
Definition at line 48 of file OccupancyGridVisualization.cpp.
| bool grid_map_visualization::OccupancyGridVisualization::readParameters | ( | XmlRpc::XmlRpcValue & | config | ) | [virtual] |
Read parameters from ROS.
| config | the parameters as XML. |
Reimplemented from grid_map_visualization::VisualizationBase.
Definition at line 26 of file OccupancyGridVisualization.cpp.
| bool grid_map_visualization::OccupancyGridVisualization::visualize | ( | const grid_map::GridMap & | map | ) | [virtual] |
Generates the visualization.
| map | the grid map to visualize. |
Implements grid_map_visualization::VisualizationBase.
Definition at line 54 of file OccupancyGridVisualization.cpp.
float grid_map_visualization::OccupancyGridVisualization::dataMax_ [private] |
Definition at line 60 of file OccupancyGridVisualization.hpp.
float grid_map_visualization::OccupancyGridVisualization::dataMin_ [private] |
Minimum and maximum value of the grid map data (used to normalize the cell data in [min, max]).
Definition at line 60 of file OccupancyGridVisualization.hpp.
std::string grid_map_visualization::OccupancyGridVisualization::layer_ [private] |
Type that is transformed to the occupancy grid.
Definition at line 57 of file OccupancyGridVisualization.hpp.