#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. More... | |
| ros::Subscriber | imageSubscriber_ |
| Image subscriber. More... | |
| std::string | imageTopic_ |
| Name of the grid map topic. More... | |
| grid_map::GridMap | map_ |
| Grid map data. More... | |
| std::string | mapFrameId_ |
| Frame id of the grid map. More... | |
| bool | mapInitialized_ |
| double | mapLengthX_ |
| Length of the grid map in x direction. More... | |
| double | maxHeight_ |
| double | minHeight_ |
| Range of the height values. More... | |
| ros::NodeHandle & | nodeHandle_ |
| ROS nodehandle. More... | |
| double | resolution_ |
| Resolution of the grid map. More... | |
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.
|
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.
| bool grid_map_demos::ImageToGridmapDemo::readParameters | ( | ) |
Reads and verifies the ROS parameters.
Definition at line 28 of file ImageToGridmapDemo.cpp.
|
private |
Grid map publisher.
Definition at line 55 of file ImageToGridmapDemo.hpp.
|
private |
Image subscriber.
Definition at line 61 of file ImageToGridmapDemo.hpp.
|
private |
Name of the grid map topic.
Definition at line 64 of file ImageToGridmapDemo.hpp.
|
private |
Grid map data.
Definition at line 58 of file ImageToGridmapDemo.hpp.
|
private |
Frame id of the grid map.
Definition at line 77 of file ImageToGridmapDemo.hpp.
|
private |
Definition at line 79 of file ImageToGridmapDemo.hpp.
|
private |
Length of the grid map in x direction.
Definition at line 67 of file ImageToGridmapDemo.hpp.
|
private |
Definition at line 74 of file ImageToGridmapDemo.hpp.
|
private |
Range of the height values.
Definition at line 73 of file ImageToGridmapDemo.hpp.
|
private |
ROS nodehandle.
Definition at line 52 of file ImageToGridmapDemo.hpp.
|
private |
Resolution of the grid map.
Definition at line 70 of file ImageToGridmapDemo.hpp.