ImageToGridmapDemo.cpp
Go to the documentation of this file.
1 /*
2  * ImageToGridmapDemo.cpp
3  *
4  * Created on: May 4, 2015
5  * Author: Péter Fankhauser
6  * Institute: ETH Zurich, ANYbotics
7  */
8 
10 
11 namespace grid_map_demos {
12 
14  : nodeHandle_(nodeHandle),
15  map_(grid_map::GridMap({"elevation"})),
16  mapInitialized_(false)
17 {
19  map_.setBasicLayers({"elevation"});
21  gridMapPublisher_ = nodeHandle_.advertise<grid_map_msgs::GridMap>("grid_map", 1, true);
22 }
23 
25 {
26 }
27 
29 {
30  nodeHandle_.param("image_topic", imageTopic_, std::string("/image"));
31  nodeHandle_.param("resolution", resolution_, 0.03);
32  nodeHandle_.param("min_height", minHeight_, 0.0);
33  nodeHandle_.param("max_height", maxHeight_, 1.0);
34  return true;
35 }
36 
37 void ImageToGridmapDemo::imageCallback(const sensor_msgs::Image& msg)
38 {
39  if (!mapInitialized_) {
41  ROS_INFO("Initialized map with size %f x %f m (%i x %i cells).", map_.getLength().x(),
42  map_.getLength().y(), map_.getSize()(0), map_.getSize()(1));
43  mapInitialized_ = true;
44  }
47 
48  // Publish as grid map.
49  grid_map_msgs::GridMap mapMessage;
51  gridMapPublisher_.publish(mapMessage);
52 }
53 
54 } /* namespace */
const Length & getLength() const
void imageCallback(const sensor_msgs::Image &msg)
void publish(const boost::shared_ptr< M > &message) const
grid_map::GridMap map_
Grid map data.
void setBasicLayers(const std::vector< std::string > &basicLayers)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
static void toMessage(const grid_map::GridMap &gridMap, grid_map_msgs::GridMap &message)
ros::Subscriber imageSubscriber_
Image subscriber.
ros::Publisher gridMapPublisher_
Grid map publisher.
double minHeight_
Range of the height values.
static bool initializeFromImage(const sensor_msgs::Image &image, const double resolution, grid_map::GridMap &gridMap, const grid_map::Position &position=grid_map::Position::Zero())
#define ROS_INFO(...)
double resolution_
Resolution of the grid map.
bool param(const std::string &param_name, T &param_val, const T &default_val) const
static bool addColorLayerFromImage(const sensor_msgs::Image &image, const std::string &layer, grid_map::GridMap &gridMap)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ImageToGridmapDemo(ros::NodeHandle &nodeHandle)
std::string imageTopic_
Name of the grid map topic.
const Size & getSize() const
ros::NodeHandle & nodeHandle_
ROS nodehandle.
static bool addLayerFromImage(const sensor_msgs::Image &image, const std::string &layer, grid_map::GridMap &gridMap, const float lowerValue=0.0, const float upperValue=1.0, const double alphaThreshold=0.5)


grid_map_demos
Author(s): Péter Fankhauser
autogenerated on Tue Jun 25 2019 20:02:37