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 <pcl/point_cloud.h>
00033 #include <pcl/point_types.h>
00034 #include <ros/time.h>
00035 #include <ros/publisher.h>
00036
00037 namespace rtabmap {
00038 class OctoMap;
00039 class Memory;
00040
00041 }
00042
00043 class MapsManager {
00044 public:
00045 MapsManager(bool usePublicNamespace);
00046 virtual ~MapsManager();
00047 void clear();
00048 bool hasSubscribers() const;
00049
00050 std::map<int, rtabmap::Transform> getFilteredPoses(
00051 const std::map<int, rtabmap::Transform> & poses);
00052
00053 std::map<int, rtabmap::Transform> updateMapCaches(
00054 const std::map<int, rtabmap::Transform> & poses,
00055 const rtabmap::Memory * memory,
00056 bool updateCloud,
00057 bool updateProj,
00058 bool updateGrid,
00059 bool updateScan,
00060 bool updateOctomap,
00061 const std::map<int, rtabmap::Signature> & signatures = std::map<int, rtabmap::Signature>());
00062
00063 void publishMaps(
00064 const std::map<int, rtabmap::Transform> & poses,
00065 const ros::Time & stamp,
00066 const std::string & mapFrameId);
00067
00068 cv::Mat generateProjMap(
00069 const std::map<int, rtabmap::Transform> & filteredPoses,
00070 float & xMin,
00071 float & yMin,
00072 float & gridCellSize);
00073
00074 cv::Mat generateGridMap(
00075 const std::map<int, rtabmap::Transform> & filteredPoses,
00076 float & xMin,
00077 float & yMin,
00078 float & gridCellSize);
00079
00080 rtabmap::OctoMap * getOctomap() const {return octomap_;}
00081
00082 private:
00083
00084 int cloudDecimation_;
00085 double cloudMaxDepth_;
00086 double cloudMinDepth_;
00087 double cloudVoxelSize_;
00088 double cloudFloorCullingHeight_;
00089 double cloudCeilingCullingHeight_;
00090 bool cloudOutputVoxelized_;
00091 bool cloudFrustumCulling_;
00092 double cloudNoiseFilteringRadius_;
00093 int cloudNoiseFilteringMinNeighbors_;
00094 int scanDecimation_;
00095 double scanVoxelSize_;
00096 bool scanOutputVoxelized_;
00097 double projMaxGroundAngle_;
00098 int projMinClusterSize_;
00099 double projMaxObstaclesHeight_;
00100 double projMaxGroundHeight_;
00101 bool projDetectFlatObstacles_;
00102 bool projMapFrame_;
00103 double gridCellSize_;
00104 double gridSize_;
00105 bool gridEroded_;
00106 bool gridUnknownSpaceFilled_;
00107 double gridMaxUnknownSpaceFilledRange_;
00108 double mapFilterRadius_;
00109 double mapFilterAngle_;
00110 bool mapCacheCleanup_;
00111 bool negativePosesIgnored_;
00112
00113 ros::Publisher cloudMapPub_;
00114 ros::Publisher projMapPub_;
00115 ros::Publisher gridMapPub_;
00116 ros::Publisher scanMapPub_;
00117 ros::Publisher octoMapPubBin_;
00118 ros::Publisher octoMapPubFull_;
00119 ros::Publisher octoMapCloud_;
00120 ros::Publisher octoMapEmptySpace_;
00121 ros::Publisher octoMapProj_;
00122
00123 std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr > clouds_;
00124 std::map<int, pcl::PointCloud<pcl::PointXYZ>::Ptr > scans_;
00125 std::map<int, std::vector<rtabmap::CameraModel> > cameraModels_;
00126 std::map<int, std::pair<cv::Mat, cv::Mat> > projMaps_;
00127 std::map<int, std::pair<cv::Mat, cv::Mat> > gridMaps_;
00128
00129 rtabmap::OctoMap * octomap_;
00130 int octomapTreeDepth_;
00131 bool octomapGroundIsObstacle_;
00132 };
00133
00134 #endif