#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. More... | |
ros::Duration | duration_ |
Duration to publish the grid map. More... | |
std::string | filePath_ |
Path the ROS bag to be published. More... | |
grid_map::GridMap | map_ |
Grid map data. More... | |
ros::NodeHandle | nodeHandle_ |
ROS nodehandle. More... | |
ros::Publisher | publisher_ |
Grid map publisher. More... | |
std::string | publishTopic_ |
Topic name of the grid map to be loaded. More... | |
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.
|
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.
void grid_map_loader::GridMapLoader::publish | ( | ) |
Publishes the grid map.
Definition at line 48 of file GridMapLoader.cpp.
bool grid_map_loader::GridMapLoader::readParameters | ( | ) |
Reads and verifies the ROS parameters.
Definition at line 31 of file GridMapLoader.cpp.
|
private |
Topic name of the grid map in the ROS bag.
Definition at line 73 of file GridMapLoader.hpp.
|
private |
Duration to publish the grid map.
Definition at line 79 of file GridMapLoader.hpp.
|
private |
Path the ROS bag to be published.
Definition at line 70 of file GridMapLoader.hpp.
|
private |
Grid map data.
Definition at line 67 of file GridMapLoader.hpp.
|
private |
ROS nodehandle.
Definition at line 61 of file GridMapLoader.hpp.
|
private |
Grid map publisher.
Definition at line 64 of file GridMapLoader.hpp.
|
private |
Topic name of the grid map to be loaded.
Definition at line 76 of file GridMapLoader.hpp.