#include <GridMapLoader.hpp>
| Public Member Functions | |
| GridMapLoader (ros::NodeHandle nodeHandle) | |
| bool | load () | 
| void | publish () | 
| bool | readParameters () | 
| virtual | ~GridMapLoader () | 
| Private Attributes | |
| std::string | bagTopic_ | 
| Topic name of the grid map in the ROS bag. | |
| ros::Duration | duration_ | 
| Duration to publish the grid map. | |
| std::string | filePath_ | 
| Path the ROS bag to be published. | |
| grid_map::GridMap | map_ | 
| Grid map data. | |
| ros::NodeHandle | nodeHandle_ | 
| ROS nodehandle. | |
| ros::Publisher | publisher_ | 
| Grid map publisher. | |
| std::string | publishTopic_ | 
| Topic name of the grid map to be loaded. | |
Loads and publishes a grid map from a bag file.
Definition at line 26 of file GridMapLoader.hpp.
| grid_map_loader::GridMapLoader::GridMapLoader | ( | ros::NodeHandle | nodeHandle | ) | 
Constructor.
| nodeHandle | the ROS node handle. | 
Definition at line 17 of file GridMapLoader.cpp.
| grid_map_loader::GridMapLoader::~GridMapLoader | ( | ) |  [virtual] | 
Destructor.
Definition at line 27 of file GridMapLoader.cpp.
| bool grid_map_loader::GridMapLoader::load | ( | ) | 
Loads the grid map from the bag file.
Definition at line 42 of file GridMapLoader.cpp.
Publishes the grid map.
Definition at line 48 of file GridMapLoader.cpp.
Reads and verifies the ROS parameters.
Definition at line 31 of file GridMapLoader.cpp.
| std::string grid_map_loader::GridMapLoader::bagTopic_  [private] | 
Topic name of the grid map in the ROS bag.
Definition at line 73 of file GridMapLoader.hpp.
Duration to publish the grid map.
Definition at line 79 of file GridMapLoader.hpp.
| std::string grid_map_loader::GridMapLoader::filePath_  [private] | 
Path the ROS bag to be published.
Definition at line 70 of file GridMapLoader.hpp.
Grid map data.
Definition at line 67 of file GridMapLoader.hpp.
ROS nodehandle.
Definition at line 61 of file GridMapLoader.hpp.
Grid map publisher.
Definition at line 64 of file GridMapLoader.hpp.
| std::string grid_map_loader::GridMapLoader::publishTopic_  [private] | 
Topic name of the grid map to be loaded.
Definition at line 76 of file GridMapLoader.hpp.