GridMapVisualization.hpp
Go to the documentation of this file.
1 /*
2  * GridMapVisualization.hpp
3  *
4  * Created on: Nov 19, 2013
5  * Author: Péter Fankhauser
6  * Institute: ETH Zurich, ANYbotics
7  *
8  */
9 
10 #pragma once
11 
12 #include <grid_map_msgs/GridMap.h>
18 
19 // ROS
20 #include <ros/ros.h>
21 
22 // STD
23 #include <vector>
24 #include <memory>
25 
27 
32 {
33  public:
34 
39  GridMapVisualization(ros::NodeHandle& nodeHandle, const std::string& parameterName);
40 
44  virtual ~GridMapVisualization();
45 
50  void callback(const grid_map_msgs::GridMap& message);
51 
52  private:
53 
58  bool readParameters();
59 
64  bool initialize();
65 
72  void updateSubscriptionCallback(const ros::TimerEvent& timerEvent);
73 
76 
79 
82 
84  std::string mapTopic_;
85 
87  std::vector<std::shared_ptr<VisualizationBase>> visualizations_;
88 
91 
94 
97 
100 };
101 
102 } /* namespace */
std::vector< std::shared_ptr< VisualizationBase > > visualizations_
List of visualizations.
ros::Timer activityCheckTimer_
Timer to check the activity of the visualizations.
bool isSubscribed_
If the grid map visualization is subscribed to the grid map.
VisualizationFactory factory_
Visualization factory.
GridMapVisualization(ros::NodeHandle &nodeHandle, const std::string &parameterName)
ros::Subscriber mapSubscriber_
ROS subscriber to the grid map.
std::string mapTopic_
Topic name of the grid map to be visualized.
void updateSubscriptionCallback(const ros::TimerEvent &timerEvent)
ros::Duration activityCheckDuration_
Duration of checking the activity of the visualizations.
void callback(const grid_map_msgs::GridMap &message)
ros::NodeHandle & nodeHandle_
ROS nodehandle.
std::string visualizationsParameter_
Parameter name of the visualizer configuration list.


grid_map_visualization
Author(s): Péter Fankhauser
autogenerated on Tue Jun 1 2021 02:13:51