28 #ifndef MAPSMANAGER_H_    29 #define MAPSMANAGER_H_    34 #include <pcl/point_cloud.h>    35 #include <pcl/point_types.h>    37 #include <ros/publisher.h>    52         bool hasSubscribers() 
const;
    55         void set2DMap(
const cv::Mat & map, 
float xMin, 
float yMin, 
float cellSize, 
const std::map<int, rtabmap::Transform> & poses, 
const rtabmap::Memory * memory = 0);
    57         std::map<int, rtabmap::Transform> getFilteredPoses(
    58                         const std::map<int, rtabmap::Transform> & poses);
    60         std::map<int, rtabmap::Transform> updateMapCaches(
    61                         const std::map<int, rtabmap::Transform> & poses,
    65                         const std::map<int, rtabmap::Signature> & signatures = std::map<int, rtabmap::Signature>());
    68                         const std::map<int, rtabmap::Transform> & poses,
    70                         const std::string & mapFrameId);
    75                         float & gridCellSize);
    77         cv::Mat getGridProbMap(
    80                         float & gridCellSize);
   123         std::map<int, std::pair< std::pair<cv::Mat, cv::Mat>, cv::Mat> > 
gridMaps_; 
 std::map< int, cv::Point3f > gridMapsViewpoints_
int cloudSubtractFilteringMinNeighbors_
const rtabmap::OccupancyGrid * getOccupancyGrid() const
ros::Publisher octoMapObstacleCloud_
std::map< int, rtabmap::Transform > gridPoses_
ros::Publisher cloudGroundPub_
const rtabmap::OctoMap * getOctomap() const
ros::Publisher gridMapPub_
rtabmap::OccupancyGrid * occupancyGrid_
ros::Publisher scanMapPub_
bool cloudOutputVoxelized_
std::map< void *, bool > latched_
ros::Publisher octoMapCloud_
std::map< std::string, std::string > ParametersMap
pcl::PointCloud< pcl::PointXYZRGB >::Ptr assembledObstacles_
std::map< int, pcl::PointCloud< pcl::PointXYZRGB >::Ptr > groundClouds_
rtabmap::OctoMap * octomap_
bool cloudSubtractFiltering_
rtabmap::ParametersMap parameters_
ros::Publisher octoMapPubFull_
ros::Publisher cloudMapPub_
ros::Publisher octoMapPubBin_
std::map< int, std::pair< std::pair< cv::Mat, cv::Mat >, cv::Mat > > gridMaps_
rtabmap::FlannIndex assembledGroundIndex_
ros::Publisher projMapPub_
rtabmap::FlannIndex assembledObstacleIndex_
bool scanEmptyRayTracing_
ros::Publisher octoMapEmptySpace_
ros::Publisher octoMapFrontierCloud_
ros::Publisher octoMapGroundCloud_
std::map< int, pcl::PointCloud< pcl::PointXYZRGB >::Ptr > obstacleClouds_
ros::Publisher octoMapProj_
pcl::PointCloud< pcl::PointXYZRGB >::Ptr assembledGround_
ros::Publisher cloudObstaclesPub_
ros::Publisher gridProbMapPub_
std::map< int, rtabmap::Transform > assembledGroundPoses_
std::map< int, rtabmap::Transform > assembledObstaclePoses_