GridMapLoader.hpp
Go to the documentation of this file.
00001 /*
00002  * GridMapLoader.hpp
00003  *
00004  *  Created on: Aug 24, 2015
00005  *      Author: Peter Fankhauser
00006  *       Institute: ETH Zurich, ANYbotics
00007  *
00008  */
00009 
00010 #pragma once
00011 
00012 // ROS
00013 #include <ros/ros.h>
00014 
00015 // Grid map
00016 #include <grid_map_ros/grid_map_ros.hpp>
00017 
00018 // STD
00019 #include <string>
00020 
00021 namespace grid_map_loader {
00022 
00026 class GridMapLoader
00027 {
00028  public:
00029 
00034   GridMapLoader(ros::NodeHandle nodeHandle);
00035 
00039   virtual ~GridMapLoader();
00040 
00045   bool readParameters();
00046 
00051   bool load();
00052 
00056   void publish();
00057 
00058  private:
00059 
00061   ros::NodeHandle nodeHandle_;
00062 
00064   ros::Publisher publisher_;
00065 
00067   grid_map::GridMap map_;
00068 
00070   std::string filePath_;
00071 
00073   std::string bagTopic_;
00074 
00076   std::string publishTopic_;
00077 
00079   ros::Duration duration_;
00080 };
00081 
00082 } /* namespace */


grid_map_loader
Author(s): Péter Fankhauser
autogenerated on Tue Jul 9 2019 05:06:41