#include <ImageToGridmapDemo.hpp>
Public Member Functions | |
void | imageCallback (const sensor_msgs::Image &msg) |
ImageToGridmapDemo (ros::NodeHandle &nodeHandle) | |
bool | readParameters () |
virtual | ~ImageToGridmapDemo () |
Private Attributes | |
ros::Publisher | gridMapPublisher_ |
Grid map publisher. | |
ros::Subscriber | imageSubscriber_ |
Image subscriber. | |
std::string | imageTopic_ |
Name of the grid map topic. | |
grid_map::GridMap | map_ |
Grid map data. | |
std::string | mapFrameId_ |
Frame id of the grid map. | |
bool | mapInitialized_ |
double | mapLengthX_ |
Length of the grid map in x direction. | |
double | maxHeight_ |
double | minHeight_ |
Range of the height values. | |
ros::NodeHandle & | nodeHandle_ |
ROS nodehandle. | |
double | resolution_ |
Resolution of the grid map. |
Loads an image and saves it as layer 'elevation' of a grid map. The grid map is published and can be viewed in Rviz.
Definition at line 26 of file ImageToGridmapDemo.hpp.
grid_map_demos::ImageToGridmapDemo::ImageToGridmapDemo | ( | ros::NodeHandle & | nodeHandle | ) |
Constructor.
nodeHandle | the ROS node handle. |
Definition at line 13 of file ImageToGridmapDemo.cpp.
grid_map_demos::ImageToGridmapDemo::~ImageToGridmapDemo | ( | ) | [virtual] |
Destructor.
Definition at line 24 of file ImageToGridmapDemo.cpp.
void grid_map_demos::ImageToGridmapDemo::imageCallback | ( | const sensor_msgs::Image & | msg | ) |
Definition at line 37 of file ImageToGridmapDemo.cpp.
Reads and verifies the ROS parameters.
Definition at line 28 of file ImageToGridmapDemo.cpp.
ros::Publisher grid_map_demos::ImageToGridmapDemo::gridMapPublisher_ [private] |
Grid map publisher.
Definition at line 55 of file ImageToGridmapDemo.hpp.
ros::Subscriber grid_map_demos::ImageToGridmapDemo::imageSubscriber_ [private] |
Image subscriber.
Definition at line 61 of file ImageToGridmapDemo.hpp.
std::string grid_map_demos::ImageToGridmapDemo::imageTopic_ [private] |
Name of the grid map topic.
Definition at line 64 of file ImageToGridmapDemo.hpp.
Grid map data.
Definition at line 58 of file ImageToGridmapDemo.hpp.
std::string grid_map_demos::ImageToGridmapDemo::mapFrameId_ [private] |
Frame id of the grid map.
Definition at line 77 of file ImageToGridmapDemo.hpp.
bool grid_map_demos::ImageToGridmapDemo::mapInitialized_ [private] |
Definition at line 79 of file ImageToGridmapDemo.hpp.
double grid_map_demos::ImageToGridmapDemo::mapLengthX_ [private] |
Length of the grid map in x direction.
Definition at line 67 of file ImageToGridmapDemo.hpp.
double grid_map_demos::ImageToGridmapDemo::maxHeight_ [private] |
Definition at line 74 of file ImageToGridmapDemo.hpp.
double grid_map_demos::ImageToGridmapDemo::minHeight_ [private] |
Range of the height values.
Definition at line 73 of file ImageToGridmapDemo.hpp.
ros::NodeHandle& grid_map_demos::ImageToGridmapDemo::nodeHandle_ [private] |
ROS nodehandle.
Definition at line 52 of file ImageToGridmapDemo.hpp.
double grid_map_demos::ImageToGridmapDemo::resolution_ [private] |
Resolution of the grid map.
Definition at line 70 of file ImageToGridmapDemo.hpp.