MapsManager.h
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #ifndef MAPSMANAGER_H_
29 #define MAPSMANAGER_H_
30 
31 #include <rtabmap/core/Signature.h>
34 #include <rtabmap/core/LocalGrid.h>
35 #include <pcl/point_cloud.h>
36 #include <pcl/point_types.h>
37 #include <ros/time.h>
38 #include <ros/publisher.h>
39 
40 namespace rtabmap {
41 class OctoMap;
42 class Memory;
43 class OccupancyGrid;
44 class LocalGridMaker;
45 class GridMap;
46 
47 } // namespace rtabmap
48 
49 namespace rtabmap_util {
50 
51 class MapsManager {
52 public:
53  MapsManager();
54  virtual ~MapsManager();
55  void init(ros::NodeHandle & nh, ros::NodeHandle & pnh, const std::string & name, bool usePublicNamespace);
56  void clear();
57  bool hasSubscribers() const;
58  bool isLatching() const {return latching_;}
59  bool isMapUpdated() const;
61  void setParameters(const rtabmap::ParametersMap & parameters);
62  void set2DMap(const cv::Mat & map, float xMin, float yMin, float cellSize, const std::map<int, rtabmap::Transform> & poses, const rtabmap::Memory * memory = 0);
63 
64  std::map<int, rtabmap::Transform> getFilteredPoses(
65  const std::map<int, rtabmap::Transform> & poses);
66 
67  std::map<int, rtabmap::Transform> updateMapCaches(
68  const std::map<int, rtabmap::Transform> & poses,
69  const rtabmap::Memory * memory,
70  bool updateGrid,
71  bool updateOctomap,
72  const std::map<int, rtabmap::Signature> & signatures = std::map<int, rtabmap::Signature>());
73 
74  void publishMaps(
75  const std::map<int, rtabmap::Transform> & poses,
76  const ros::Time & stamp,
77  const std::string & mapFrameId);
78 
79  cv::Mat getGridMap(
80  float & xMin,
81  float & yMin,
82  float & gridCellSize);
83 
84  cv::Mat getGridProbMap(
85  float & xMin,
86  float & yMin,
87  float & gridCellSize);
88 
89  const rtabmap::OctoMap * getOctomap() const {return octomap_;}
92 
93 private:
94  // mapping stuff
103 
120 
121  std::map<int, rtabmap::Transform> assembledGroundPoses_;
122  std::map<int, rtabmap::Transform> assembledObstaclePoses_;
123  pcl::PointCloud<pcl::PointXYZRGB>::Ptr assembledObstacles_;
124  pcl::PointCloud<pcl::PointXYZRGB>::Ptr assembledGround_;
127  std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr > groundClouds_;
128  std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr > obstacleClouds_;
129 
131 
135 
139 
142 
144 
145  bool latching_;
146  std::map<void*, bool> latched_;
147 };
148 
149 } // namespace rtabmap_util
150 
151 #endif /* MAPSMANAGER_H_ */
rtabmap_util::MapsManager::parameters_
rtabmap::ParametersMap parameters_
Definition: MapsManager.h:143
rtabmap_util::MapsManager::octoMapGroundCloud_
ros::Publisher octoMapGroundCloud_
Definition: MapsManager.h:115
rtabmap_util::MapsManager::getGridProbMap
cv::Mat getGridProbMap(float &xMin, float &yMin, float &gridCellSize)
Definition: MapsManager.cpp:1527
rtabmap_util::MapsManager::localMapMaker_
rtabmap::LocalGridMaker * localMapMaker_
Definition: MapsManager.h:133
rtabmap_util::MapsManager::cloudObstaclesPub_
ros::Publisher cloudObstaclesPub_
Definition: MapsManager.h:106
FlannIndex.h
LocalGrid.h
name
ros::Publisher
rtabmap_util::MapsManager::octoMapEmptySpace_
ros::Publisher octoMapEmptySpace_
Definition: MapsManager.h:117
rtabmap_util::MapsManager::isMapUpdated
bool isMapUpdated() const
Definition: MapsManager.cpp:434
rtabmap_util::MapsManager::MapsManager
MapsManager()
Definition: MapsManager.cpp:64
time.h
rtabmap_util::MapsManager::assembledGroundPoses_
std::map< int, rtabmap::Transform > assembledGroundPoses_
Definition: MapsManager.h:121
rtabmap_util::MapsManager::getOctomap
const rtabmap::OctoMap * getOctomap() const
Definition: MapsManager.h:89
rtabmap_util::MapsManager::cloudMapPub_
ros::Publisher cloudMapPub_
Definition: MapsManager.h:104
rtabmap_util::MapsManager
Definition: MapsManager.h:51
rtabmap_util::MapsManager::cloudGroundPub_
ros::Publisher cloudGroundPub_
Definition: MapsManager.h:105
rtabmap::LocalGridCache
rtabmap_util::MapsManager::scanMapPub_
ros::Publisher scanMapPub_
Definition: MapsManager.h:110
rtabmap_util::MapsManager::isLatching
bool isLatching() const
Definition: MapsManager.h:58
rtabmap_util::MapsManager::alwaysUpdateMap_
bool alwaysUpdateMap_
Definition: MapsManager.h:101
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
rtabmap_util
Definition: MapsManager.h:49
rtabmap_util::MapsManager::occupancyGrid_
rtabmap::OccupancyGrid * occupancyGrid_
Definition: MapsManager.h:132
rtabmap::GridMap
rtabmap::OccupancyGrid
rtabmap_util::MapsManager::octoMapCloud_
ros::Publisher octoMapCloud_
Definition: MapsManager.h:113
rtabmap_util::MapsManager::clear
void clear()
Definition: MapsManager.cpp:390
rtabmap_util::MapsManager::groundClouds_
std::map< int, pcl::PointCloud< pcl::PointXYZRGB >::Ptr > groundClouds_
Definition: MapsManager.h:127
rtabmap_util::MapsManager::octomap_
rtabmap::OctoMap * octomap_
Definition: MapsManager.h:136
rtabmap_util::MapsManager::cloudSubtractFilteringMinNeighbors_
int cloudSubtractFilteringMinNeighbors_
Definition: MapsManager.h:97
rtabmap_util::MapsManager::assembledObstacles_
pcl::PointCloud< pcl::PointXYZRGB >::Ptr assembledObstacles_
Definition: MapsManager.h:123
rtabmap_util::MapsManager::octoMapPubBin_
ros::Publisher octoMapPubBin_
Definition: MapsManager.h:111
rtabmap_util::MapsManager::gridUpdated_
bool gridUpdated_
Definition: MapsManager.h:134
rtabmap_util::MapsManager::mapFilterAngle_
double mapFilterAngle_
Definition: MapsManager.h:99
rtabmap_util::MapsManager::~MapsManager
virtual ~MapsManager()
Definition: MapsManager.cpp:221
rtabmap_util::MapsManager::localMaps_
rtabmap::LocalGridCache localMaps_
Definition: MapsManager.h:130
rtabmap_util::MapsManager::getFilteredPoses
std::map< int, rtabmap::Transform > getFilteredPoses(const std::map< int, rtabmap::Transform > &poses)
Definition: MapsManager.cpp:446
rtabmap::LocalGridMaker
rtabmap_util::MapsManager::mapCacheCleanup_
bool mapCacheCleanup_
Definition: MapsManager.h:100
rtabmap_util::MapsManager::elevationMapPub_
ros::Publisher elevationMapPub_
Definition: MapsManager.h:119
rtabmap_util::MapsManager::gridProbMapPub_
ros::Publisher gridProbMapPub_
Definition: MapsManager.h:109
rtabmap_util::MapsManager::octoMapProj_
ros::Publisher octoMapProj_
Definition: MapsManager.h:118
rtabmap_util::MapsManager::assembledGround_
pcl::PointCloud< pcl::PointXYZRGB >::Ptr assembledGround_
Definition: MapsManager.h:124
rtabmap_util::MapsManager::mapFilterRadius_
double mapFilterRadius_
Definition: MapsManager.h:98
rtabmap::FlannIndex
rtabmap_util::MapsManager::set2DMap
void set2DMap(const cv::Mat &map, float xMin, float yMin, float cellSize, const std::map< int, rtabmap::Transform > &poses, const rtabmap::Memory *memory=0)
Definition: MapsManager.cpp:348
rtabmap_util::MapsManager::scanEmptyRayTracing_
bool scanEmptyRayTracing_
Definition: MapsManager.h:102
rtabmap_util::MapsManager::getGridMap
cv::Mat getGridMap(float &xMin, float &yMin, float &gridCellSize)
Definition: MapsManager.cpp:1518
rtabmap_util::MapsManager::assembledObstaclePoses_
std::map< int, rtabmap::Transform > assembledObstaclePoses_
Definition: MapsManager.h:122
rtabmap_util::MapsManager::elevationMap_
rtabmap::GridMap * elevationMap_
Definition: MapsManager.h:140
rtabmap_util::MapsManager::assembledGroundIndex_
rtabmap::FlannIndex assembledGroundIndex_
Definition: MapsManager.h:125
rtabmap_util::MapsManager::latching_
bool latching_
Definition: MapsManager.h:145
rtabmap_util::MapsManager::obstacleClouds_
std::map< int, pcl::PointCloud< pcl::PointXYZRGB >::Ptr > obstacleClouds_
Definition: MapsManager.h:128
rtabmap_util::MapsManager::hasSubscribers
bool hasSubscribers() const
Definition: MapsManager.cpp:414
rtabmap_util::MapsManager::getOccupancyGrid
const rtabmap::OccupancyGrid * getOccupancyGrid() const
Definition: MapsManager.h:90
rtabmap_util::MapsManager::init
void init(ros::NodeHandle &nh, ros::NodeHandle &pnh, const std::string &name, bool usePublicNamespace)
Definition: MapsManager.cpp:95
rtabmap_util::MapsManager::octoMapObstacleCloud_
ros::Publisher octoMapObstacleCloud_
Definition: MapsManager.h:116
rtabmap_util::MapsManager::cloudOutputVoxelized_
bool cloudOutputVoxelized_
Definition: MapsManager.h:95
ros::Time
rtabmap_util::MapsManager::octomapTreeDepth_
int octomapTreeDepth_
Definition: MapsManager.h:137
rtabmap_util::MapsManager::elevationMapUpdated_
bool elevationMapUpdated_
Definition: MapsManager.h:141
rtabmap::Memory
Signature.h
rtabmap_util::MapsManager::latched_
std::map< void *, bool > latched_
Definition: MapsManager.h:146
Parameters.h
rtabmap::OctoMap
rtabmap_util::MapsManager::assembledObstacleIndex_
rtabmap::FlannIndex assembledObstacleIndex_
Definition: MapsManager.h:126
rtabmap_util::MapsManager::getLocalMapMaker
const rtabmap::LocalGridMaker * getLocalMapMaker() const
Definition: MapsManager.h:91
rtabmap_util::MapsManager::projMapPub_
ros::Publisher projMapPub_
Definition: MapsManager.h:107
rtabmap_util::MapsManager::cloudSubtractFiltering_
bool cloudSubtractFiltering_
Definition: MapsManager.h:96
rtabmap
rtabmap_util::MapsManager::setParameters
void setParameters(const rtabmap::ParametersMap &parameters)
Definition: MapsManager.cpp:329
rtabmap_util::MapsManager::updateMapCaches
std::map< int, rtabmap::Transform > updateMapCaches(const std::map< int, rtabmap::Transform > &poses, const rtabmap::Memory *memory, bool updateGrid, bool updateOctomap, const std::map< int, rtabmap::Signature > &signatures=std::map< int, rtabmap::Signature >())
Definition: MapsManager.cpp:457
rtabmap_util::MapsManager::octoMapPubFull_
ros::Publisher octoMapPubFull_
Definition: MapsManager.h:112
ros::NodeHandle
rtabmap_util::MapsManager::backwardCompatibilityParameters
void backwardCompatibilityParameters(ros::NodeHandle &pnh, rtabmap::ParametersMap &parameters) const
Definition: MapsManager.cpp:289
rtabmap_util::MapsManager::octomapUpdated_
bool octomapUpdated_
Definition: MapsManager.h:138
rtabmap_util::MapsManager::publishMaps
void publishMaps(const std::map< int, rtabmap::Transform > &poses, const ros::Time &stamp, const std::string &mapFrameId)
Definition: MapsManager.cpp:777
rtabmap_util::MapsManager::gridMapPub_
ros::Publisher gridMapPub_
Definition: MapsManager.h:108
rtabmap_util::MapsManager::octoMapFrontierCloud_
ros::Publisher octoMapFrontierCloud_
Definition: MapsManager.h:114


rtabmap_util
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:40:50