#include <OctomapToGridmapDemo.hpp>
Public Member Functions | |
void | convertAndPublishMap () |
OctomapToGridmapDemo (ros::NodeHandle &nodeHandle) | |
bool | readParameters () |
virtual | ~OctomapToGridmapDemo () |
Private Attributes | |
ros::ServiceClient | client_ |
Octomap service client. | |
ros::Publisher | gridMapPublisher_ |
Grid map publisher. | |
grid_map::GridMap | map_ |
Grid map data. | |
float | maxX_ |
float | maxY_ |
float | maxZ_ |
float | minX_ |
Bounding box of octomap to convert. | |
float | minY_ |
float | minZ_ |
ros::NodeHandle & | nodeHandle_ |
ROS nodehandle. | |
ros::Publisher | octomapPublisher_ |
Octomap publisher. | |
std::string | octomapServiceTopic_ |
Name of the grid map topic. |
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.
Constructor.
nodeHandle | the ROS node handle. |
Definition at line 20 of file OctomapToGridmapDemo.cpp.
virtual grid_map_demos::OctomapToGridmapDemo::~OctomapToGridmapDemo | ( | ) | [virtual] |
Destructor.
Reads and verifies the ROS parameters.
Octomap service client.
Definition at line 65 of file OctomapToGridmapDemo.hpp.
Grid map publisher.
Definition at line 53 of file OctomapToGridmapDemo.hpp.
Grid map data.
Definition at line 59 of file OctomapToGridmapDemo.hpp.
float grid_map_demos::OctomapToGridmapDemo::maxX_ [private] |
Definition at line 69 of file OctomapToGridmapDemo.hpp.
float grid_map_demos::OctomapToGridmapDemo::maxY_ [private] |
Definition at line 71 of file OctomapToGridmapDemo.hpp.
float grid_map_demos::OctomapToGridmapDemo::maxZ_ [private] |
Definition at line 73 of file OctomapToGridmapDemo.hpp.
float grid_map_demos::OctomapToGridmapDemo::minX_ [private] |
Bounding box of octomap to convert.
Definition at line 68 of file OctomapToGridmapDemo.hpp.
float grid_map_demos::OctomapToGridmapDemo::minY_ [private] |
Definition at line 70 of file OctomapToGridmapDemo.hpp.
float grid_map_demos::OctomapToGridmapDemo::minZ_ [private] |
Definition at line 72 of file OctomapToGridmapDemo.hpp.
ROS nodehandle.
Definition at line 50 of file OctomapToGridmapDemo.hpp.
Octomap publisher.
Definition at line 56 of file OctomapToGridmapDemo.hpp.
std::string grid_map_demos::OctomapToGridmapDemo::octomapServiceTopic_ [private] |
Name of the grid map topic.
Definition at line 62 of file OctomapToGridmapDemo.hpp.