Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #ifndef MAPSMANAGER_H_
00029 #define MAPSMANAGER_H_
00030
00031 #include <rtabmap/core/Signature.h>
00032 #include <rtabmap/core/Parameters.h>
00033 #include <rtabmap/core/FlannIndex.h>
00034 #include <pcl/point_cloud.h>
00035 #include <pcl/point_types.h>
00036 #include <ros/time.h>
00037 #include <ros/publisher.h>
00038
00039 namespace rtabmap {
00040 class OctoMap;
00041 class Memory;
00042 class OccupancyGrid;
00043
00044 }
00045
00046 class MapsManager {
00047 public:
00048 MapsManager();
00049 virtual ~MapsManager();
00050 void init(ros::NodeHandle & nh, ros::NodeHandle & pnh, const std::string & name, bool usePublicNamespace);
00051 void clear();
00052 bool hasSubscribers() const;
00053 void backwardCompatibilityParameters(ros::NodeHandle & pnh, rtabmap::ParametersMap & parameters) const;
00054 void setParameters(const rtabmap::ParametersMap & parameters);
00055 void set2DMap(const cv::Mat & map, float xMin, float yMin, float cellSize, const std::map<int, rtabmap::Transform> & poses, const rtabmap::Memory * memory = 0);
00056
00057 std::map<int, rtabmap::Transform> getFilteredPoses(
00058 const std::map<int, rtabmap::Transform> & poses);
00059
00060 std::map<int, rtabmap::Transform> updateMapCaches(
00061 const std::map<int, rtabmap::Transform> & poses,
00062 const rtabmap::Memory * memory,
00063 bool updateGrid,
00064 bool updateOctomap,
00065 const std::map<int, rtabmap::Signature> & signatures = std::map<int, rtabmap::Signature>());
00066
00067 void publishMaps(
00068 const std::map<int, rtabmap::Transform> & poses,
00069 const ros::Time & stamp,
00070 const std::string & mapFrameId);
00071
00072 cv::Mat getGridMap(
00073 float & xMin,
00074 float & yMin,
00075 float & gridCellSize);
00076
00077 cv::Mat getGridProbMap(
00078 float & xMin,
00079 float & yMin,
00080 float & gridCellSize);
00081
00082 const rtabmap::OctoMap * getOctomap() const {return octomap_;}
00083 const rtabmap::OccupancyGrid * getOccupancyGrid() const {return occupancyGrid_;}
00084
00085 private:
00086
00087 bool cloudOutputVoxelized_;
00088 bool cloudSubtractFiltering_;
00089 int cloudSubtractFilteringMinNeighbors_;
00090 double mapFilterRadius_;
00091 double mapFilterAngle_;
00092 bool mapCacheCleanup_;
00093 bool negativePosesIgnored_;
00094 bool negativeScanEmptyRayTracing_;
00095
00096 ros::Publisher cloudMapPub_;
00097 ros::Publisher cloudGroundPub_;
00098 ros::Publisher cloudObstaclesPub_;
00099 ros::Publisher projMapPub_;
00100 ros::Publisher gridMapPub_;
00101 ros::Publisher gridProbMapPub_;
00102 ros::Publisher scanMapPub_;
00103 ros::Publisher octoMapPubBin_;
00104 ros::Publisher octoMapPubFull_;
00105 ros::Publisher octoMapCloud_;
00106 ros::Publisher octoMapGroundCloud_;
00107 ros::Publisher octoMapObstacleCloud_;
00108 ros::Publisher octoMapEmptySpace_;
00109 ros::Publisher octoMapProj_;
00110
00111 std::map<int, rtabmap::Transform> assembledGroundPoses_;
00112 std::map<int, rtabmap::Transform> assembledObstaclePoses_;
00113 pcl::PointCloud<pcl::PointXYZRGB>::Ptr assembledObstacles_;
00114 pcl::PointCloud<pcl::PointXYZRGB>::Ptr assembledGround_;
00115 rtabmap::FlannIndex assembledGroundIndex_;
00116 rtabmap::FlannIndex assembledObstacleIndex_;
00117 std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr > groundClouds_;
00118 std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr > obstacleClouds_;
00119
00120 std::map<int, rtabmap::Transform> gridPoses_;
00121 cv::Mat gridMap_;
00122 std::map<int, std::pair< std::pair<cv::Mat, cv::Mat>, cv::Mat> > gridMaps_;
00123 std::map<int, cv::Point3f> gridMapsViewpoints_;
00124
00125 rtabmap::OccupancyGrid * occupancyGrid_;
00126
00127 rtabmap::OctoMap * octomap_;
00128 int octomapTreeDepth_;
00129
00130 rtabmap::ParametersMap parameters_;
00131 };
00132
00133 #endif