#include <GridMapVisualization.hpp>
Visualizes a grid map by publishing different topics that can be viewed in Rviz.
Definition at line 31 of file GridMapVisualization.hpp.
grid_map_visualization::GridMapVisualization::GridMapVisualization |
( |
ros::NodeHandle & |
nodeHandle, |
|
|
const std::string & |
parameterName |
|
) |
| |
grid_map_visualization::GridMapVisualization::~GridMapVisualization |
( |
| ) |
|
|
virtual |
void grid_map_visualization::GridMapVisualization::callback |
( |
const grid_map_msgs::GridMap & |
message | ) |
|
Callback function for the grid map.
- Parameters
-
message | the grid map message to be visualized. |
Definition at line 158 of file GridMapVisualization.cpp.
bool grid_map_visualization::GridMapVisualization::initialize |
( |
| ) |
|
|
private |
bool grid_map_visualization::GridMapVisualization::readParameters |
( |
| ) |
|
|
private |
void grid_map_visualization::GridMapVisualization::updateSubscriptionCallback |
( |
const ros::TimerEvent & |
timerEvent | ) |
|
|
private |
Check if visualizations are active (subscribed to), and accordingly cancels/activates the subscription to the grid map to safe bandwidth.
- Parameters
-
timerEvent | the timer event. |
Definition at line 135 of file GridMapVisualization.cpp.
ros::Duration grid_map_visualization::GridMapVisualization::activityCheckDuration_ |
|
private |
ros::Timer grid_map_visualization::GridMapVisualization::activityCheckTimer_ |
|
private |
bool grid_map_visualization::GridMapVisualization::isSubscribed_ |
|
private |
ros::Subscriber grid_map_visualization::GridMapVisualization::mapSubscriber_ |
|
private |
std::string grid_map_visualization::GridMapVisualization::mapTopic_ |
|
private |
std::vector<std::shared_ptr<VisualizationBase> > grid_map_visualization::GridMapVisualization::visualizations_ |
|
private |
std::string grid_map_visualization::GridMapVisualization::visualizationsParameter_ |
|
private |
The documentation for this class was generated from the following files: