#include <PointCloudVisualization.hpp>
Public Member Functions | |
bool | initialize () |
PointCloudVisualization (ros::NodeHandle &nodeHandle, const std::string &name) | |
bool | readParameters (XmlRpc::XmlRpcValue &config) |
bool | visualize (const grid_map::GridMap &map) |
virtual | ~PointCloudVisualization () |
Private Attributes | |
std::string | layer_ |
Type that is transformed to points. |
Visualization of the grid map as a point cloud.
Definition at line 22 of file PointCloudVisualization.hpp.
grid_map_visualization::PointCloudVisualization::PointCloudVisualization | ( | ros::NodeHandle & | nodeHandle, |
const std::string & | name | ||
) |
Constructor.
nodeHandle | the ROS node handle. |
name | the name of the visualization. |
Definition at line 16 of file PointCloudVisualization.cpp.
Destructor.
Definition at line 21 of file PointCloudVisualization.cpp.
bool grid_map_visualization::PointCloudVisualization::initialize | ( | ) | [virtual] |
Initialization.
Implements grid_map_visualization::VisualizationBase.
Definition at line 35 of file PointCloudVisualization.cpp.
bool grid_map_visualization::PointCloudVisualization::readParameters | ( | XmlRpc::XmlRpcValue & | config | ) | [virtual] |
Read parameters from ROS.
config | the parameters as XML. |
Reimplemented from grid_map_visualization::VisualizationBase.
Definition at line 25 of file PointCloudVisualization.cpp.
bool grid_map_visualization::PointCloudVisualization::visualize | ( | const grid_map::GridMap & | map | ) | [virtual] |
Generates the visualization.
map | the grid map to visualize. |
Implements grid_map_visualization::VisualizationBase.
Definition at line 41 of file PointCloudVisualization.cpp.
std::string grid_map_visualization::PointCloudVisualization::layer_ [private] |
Type that is transformed to points.
Definition at line 59 of file PointCloudVisualization.hpp.