#include <VisualizationBase.hpp>

| Public Member Functions | |
| virtual bool | initialize ()=0 | 
| bool | isActive () const | 
| virtual bool | readParameters (XmlRpc::XmlRpcValue &config) | 
| VisualizationBase (ros::NodeHandle &nodeHandle, const std::string &name) | |
| virtual bool | visualize (const grid_map::GridMap &map)=0 | 
| virtual | ~VisualizationBase () | 
| Protected Member Functions | |
| 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 | |
| std::string | name_ | 
| Name of the visualization. | |
| ros::NodeHandle & | nodeHandle_ | 
| ROS nodehandle. | |
| StringMap | parameters_ | 
| Storage of the parsed XML parameters. | |
| ros::Publisher | publisher_ | 
| ROS publisher of the occupancy grid. | |
Definition at line 20 of file VisualizationBase.hpp.
| grid_map_visualization::VisualizationBase::VisualizationBase | ( | ros::NodeHandle & | nodeHandle, | 
| const std::string & | name | ||
| ) | 
Constructor.
| nodeHandle | the ROS node handle. | 
| name | the name of the visualization. | 
Definition at line 13 of file VisualizationBase.cpp.
Destructor.
Definition at line 19 of file VisualizationBase.cpp.
| bool grid_map_visualization::VisualizationBase::getParam | ( | const std::string & | name, | 
| std::string & | value | ||
| ) |  [protected] | 
Get a visualization parameter as a string.
| [in] | name | the name of the parameter | 
| [out] | value | the string to set with the value. | 
Definition at line 53 of file VisualizationBase.cpp.
| bool grid_map_visualization::VisualizationBase::getParam | ( | const std::string & | name, | 
| double & | value | ||
| ) |  [protected] | 
Get a visualization parameter as a double.
| [in] | name | the name of the parameter | 
| [out] | value | the double to set with the value. | 
Definition at line 62 of file VisualizationBase.cpp.
| bool grid_map_visualization::VisualizationBase::getParam | ( | const std::string & | name, | 
| float & | value | ||
| ) |  [protected] | 
Get a visualization parameter as a float.
| [in] | name | the name of the parameter | 
| [out] | value | the float to set with the value. | 
Definition at line 73 of file VisualizationBase.cpp.
| bool grid_map_visualization::VisualizationBase::getParam | ( | const std::string & | name, | 
| int & | value | ||
| ) |  [protected] | 
Get a visualization parameter as an integer.
| [in] | name | the name of the parameter | 
| [out] | value | the int to set with the value. | 
Definition at line 90 of file VisualizationBase.cpp.
| bool grid_map_visualization::VisualizationBase::getParam | ( | const std::string & | name, | 
| bool & | value | ||
| ) |  [protected] | 
Get a visualization parameter as a boolean.
| [in] | name | the name of the parameter | 
| [out] | value | the boolean to set with the value. | 
Definition at line 81 of file VisualizationBase.cpp.
| virtual bool grid_map_visualization::VisualizationBase::initialize | ( | ) |  [pure virtual] | 
Initialization.
Implemented in grid_map_visualization::VectorVisualization, grid_map_visualization::MapRegionVisualization, grid_map_visualization::FlatPointCloudVisualization, grid_map_visualization::PointCloudVisualization, grid_map_visualization::GridCellsVisualization, and grid_map_visualization::OccupancyGridVisualization.
| bool grid_map_visualization::VisualizationBase::isActive | ( | ) | const | 
Checks if visualization is active (if somebody has actually subscribed).
Definition at line 23 of file VisualizationBase.cpp.
| bool grid_map_visualization::VisualizationBase::readParameters | ( | XmlRpc::XmlRpcValue & | config | ) |  [virtual] | 
Read parameters from ROS.
| config | the parameters as XML. | 
Reimplemented in grid_map_visualization::VectorVisualization, grid_map_visualization::MapRegionVisualization, grid_map_visualization::FlatPointCloudVisualization, grid_map_visualization::PointCloudVisualization, grid_map_visualization::GridCellsVisualization, and grid_map_visualization::OccupancyGridVisualization.
Definition at line 29 of file VisualizationBase.cpp.
| virtual bool grid_map_visualization::VisualizationBase::visualize | ( | const grid_map::GridMap & | map | ) |  [pure virtual] | 
Generates the visualization.
| map | the grid map to visualize. | 
Implemented in grid_map_visualization::VectorVisualization, grid_map_visualization::MapRegionVisualization, grid_map_visualization::FlatPointCloudVisualization, grid_map_visualization::PointCloudVisualization, grid_map_visualization::GridCellsVisualization, and grid_map_visualization::OccupancyGridVisualization.
| std::string grid_map_visualization::VisualizationBase::name_  [protected] | 
Name of the visualization.
Definition at line 107 of file VisualizationBase.hpp.
ROS nodehandle.
Definition at line 104 of file VisualizationBase.hpp.
Storage of the parsed XML parameters.
Definition at line 110 of file VisualizationBase.hpp.
ROS publisher of the occupancy grid.
Definition at line 113 of file VisualizationBase.hpp.