#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 () |
Public Member Functions inherited from grid_map_visualization::VisualizationBase | |
| bool | isActive () const |
| VisualizationBase (ros::NodeHandle &nodeHandle, const std::string &name) | |
| virtual | ~VisualizationBase () |
Private Attributes | |
| std::string | layer_ |
| Type that is transformed to the occupancy grid. More... | |
| float | lowerThreshold_ |
| Values that are between lower and upper threshold are shown. More... | |
| float | upperThreshold_ |
Additional Inherited Members | |
Protected Member Functions inherited from grid_map_visualization::VisualizationBase | |
| bool | getParam (const std::string &name, std::string &value) |
| bool | getParam (const std::string &name, double &value) |
| bool | getParam (const std::string &name, float &value) |
| bool | getParam (const std::string &name, int &value) |
| bool | getParam (const std::string &name, bool &value) |
Protected Attributes inherited from grid_map_visualization::VisualizationBase | |
| std::string | name_ |
| Name of the visualization. More... | |
| ros::NodeHandle & | nodeHandle_ |
| ROS nodehandle. More... | |
| StringMap | parameters_ |
| Storage of the parsed XML parameters. More... | |
| ros::Publisher | publisher_ |
| ROS publisher of the occupancy grid. More... | |
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.
|
virtual |
Destructor.
Definition at line 25 of file GridCellsVisualization.cpp.
|
virtual |
Initialization.
Implements grid_map_visualization::VisualizationBase.
Definition at line 49 of file GridCellsVisualization.cpp.
|
virtual |
Read parameters from ROS.
| config | the parameters as XML. |
Reimplemented from grid_map_visualization::VisualizationBase.
Definition at line 29 of file GridCellsVisualization.cpp.
|
virtual |
Generates the visualization.
| map | the grid map to visualize. |
Implements grid_map_visualization::VisualizationBase.
Definition at line 55 of file GridCellsVisualization.cpp.
|
private |
Type that is transformed to the occupancy grid.
Definition at line 57 of file GridCellsVisualization.hpp.
|
private |
Values that are between lower and upper threshold are shown.
Definition at line 60 of file GridCellsVisualization.hpp.
|
private |
Definition at line 60 of file GridCellsVisualization.hpp.