00001 /* 00002 * GridMapVisualization.hpp 00003 * 00004 * Created on: Nov 19, 2013 00005 * Author: Péter Fankhauser 00006 * Institute: ETH Zurich, ANYbotics 00007 * 00008 */ 00009 00010 #pragma once 00011 00012 #include <grid_map_msgs/GridMap.h> 00013 #include <grid_map_visualization/visualizations/VisualizationFactory.hpp> 00014 #include <grid_map_visualization/visualizations/MapRegionVisualization.hpp> 00015 #include <grid_map_visualization/visualizations/PointCloudVisualization.hpp> 00016 #include <grid_map_visualization/visualizations/VectorVisualization.hpp> 00017 #include <grid_map_visualization/visualizations/OccupancyGridVisualization.hpp> 00018 00019 // ROS 00020 #include <ros/ros.h> 00021 00022 // STD 00023 #include <vector> 00024 #include <memory> 00025 00026 namespace grid_map_visualization { 00027 00031 class GridMapVisualization 00032 { 00033 public: 00034 00039 GridMapVisualization(ros::NodeHandle& nodeHandle, const std::string& parameterName); 00040 00044 virtual ~GridMapVisualization(); 00045 00050 void callback(const grid_map_msgs::GridMap& message); 00051 00052 private: 00053 00058 bool readParameters(); 00059 00064 bool initialize(); 00065 00072 void updateSubscriptionCallback(const ros::TimerEvent& timerEvent); 00073 00075 ros::NodeHandle& nodeHandle_; 00076 00078 std::string visualizationsParameter_; 00079 00081 ros::Subscriber mapSubscriber_; 00082 00084 std::string mapTopic_; 00085 00087 std::vector<std::shared_ptr<VisualizationBase>> visualizations_; 00088 00090 VisualizationFactory factory_; 00091 00093 ros::Timer activityCheckTimer_; 00094 00096 ros::Duration activityCheckDuration_; 00097 00099 bool isSubscribed_; 00100 }; 00101 00102 } /* namespace */