Skip to content
Snippets Groups Projects
MapManager.h 2.09 KiB
Newer Older
#ifndef MAPMANAGER_H
#define MAPMANAGER_H

#include <string>
#include <map>
#include <list>

#include "nav_msgs/OccupancyGrid.h"
#include "geometry_msgs/Pose.h"

#include "ros/ros.h"

/** @class MapManager
  * @author Malte Knauf, David Gossow (RX), Susanne Maur
  * @brief This class holds all current map layers, updates them and publishes them in one merged map.
  */
class MapManager
{
  public:

    /**
     * @brief Constructor
     * @param nh node handle
     */
    MapManager(ros::NodeHandle* nh);

    /**
     * @brief getMapLayer search for map layer of given type and return it
     * @param type type of map layer to search for
     * @return map layer
     */
    nav_msgs::OccupancyGrid::ConstPtr getMapLayer(int type);

    /**
     * @brief updateMapLayer replaces map layer of given type
     * @param type type of map layer
     * @param layer new map layer
     */
    void updateMapLayer(int type, nav_msgs::OccupancyGrid::ConstPtr layer);

    /**
     * @brief toggleMapVisibility toggles visibility of each map layer
     * @param type type of map layer to toggle
     * @param state visible or not
     */
    void toggleMapVisibility(int type, bool state );

    /**
     * @brief clearMapLayers Clear all map layers
     */
    void clearMapLayers();

    /** getters */
    double getHeight() { return m_Height; }
    double getWidth() { return m_Width; }
    double getResolution() { return m_Resolution; }
    geometry_msgs::Pose getOrigin() { return m_Origin; }

    /** destructor */
    virtual ~MapManager();

  private:

    /** merges all map layers and publishes the merged map */
    void sendMergedMap();

    /**
     * The map data of each available map layer ist stored in this map
     */
    std::map<int, nav_msgs::OccupancyGrid::ConstPtr > m_MapLayers;

    /**
     * This map stores which map layers are enabled and which are disabled
     */
    std::map<int, bool> m_MapVisibility;

    //sizes of the last slam map
    double m_Height;
    double m_Width;
    double m_Resolution;
    geometry_msgs::Pose m_Origin;

    /** map publisher */
    ros::Publisher m_MapPublisher;
};
#endif