#include <OctomapToGridmapDemo.hpp>
Public Member Functions | |
void | convertAndPublishMap () |
OctomapToGridmapDemo (ros::NodeHandle &nodeHandle) | |
bool | readParameters () |
virtual | ~OctomapToGridmapDemo () |
Private Attributes | |
ros::ServiceClient | client_ |
Octomap service client. More... | |
ros::Publisher | gridMapPublisher_ |
Grid map publisher. More... | |
grid_map::GridMap | map_ |
Grid map data. More... | |
float | maxX_ |
float | maxY_ |
float | maxZ_ |
float | minX_ |
Bounding box of octomap to convert. More... | |
float | minY_ |
float | minZ_ |
ros::NodeHandle & | nodeHandle_ |
ROS nodehandle. More... | |
ros::Publisher | octomapPublisher_ |
Octomap publisher. More... | |
std::string | octomapServiceTopic_ |
Name of the grid map topic. More... | |
Receives a volumetric OctoMap and converts it to a grid map with an elevation layer. The grid map is published and can be viewed in Rviz.
Definition at line 24 of file OctomapToGridmapDemo.hpp.
grid_map_demos::OctomapToGridmapDemo::OctomapToGridmapDemo | ( | ros::NodeHandle & | nodeHandle | ) |
Constructor.
nodeHandle | the ROS node handle. |
Definition at line 20 of file OctomapToGridmapDemo.cpp.
|
virtual |
Destructor.
Definition at line 31 of file OctomapToGridmapDemo.cpp.
void grid_map_demos::OctomapToGridmapDemo::convertAndPublishMap | ( | ) |
Definition at line 47 of file OctomapToGridmapDemo.cpp.
bool grid_map_demos::OctomapToGridmapDemo::readParameters | ( | ) |
Reads and verifies the ROS parameters.
Definition at line 35 of file OctomapToGridmapDemo.cpp.
|
private |
Octomap service client.
Definition at line 65 of file OctomapToGridmapDemo.hpp.
|
private |
Grid map publisher.
Definition at line 53 of file OctomapToGridmapDemo.hpp.
|
private |
Grid map data.
Definition at line 59 of file OctomapToGridmapDemo.hpp.
|
private |
Definition at line 69 of file OctomapToGridmapDemo.hpp.
|
private |
Definition at line 71 of file OctomapToGridmapDemo.hpp.
|
private |
Definition at line 73 of file OctomapToGridmapDemo.hpp.
|
private |
Bounding box of octomap to convert.
Definition at line 68 of file OctomapToGridmapDemo.hpp.
|
private |
Definition at line 70 of file OctomapToGridmapDemo.hpp.
|
private |
Definition at line 72 of file OctomapToGridmapDemo.hpp.
|
private |
ROS nodehandle.
Definition at line 50 of file OctomapToGridmapDemo.hpp.
|
private |
Octomap publisher.
Definition at line 56 of file OctomapToGridmapDemo.hpp.
|
private |
Name of the grid map topic.
Definition at line 62 of file OctomapToGridmapDemo.hpp.