14 : nodeHandle_(nodeHandle),
15 map_(
grid_map::GridMap({
"elevation"})),
49 grid_map_msgs::GridMap mapMessage;
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())
Node for comparing different normal filters performances.
double resolution_
Resolution of the grid map.
bool param(const std::string ¶m_name, T ¶m_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.
virtual ~ImageToGridmapDemo()
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)