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 <pcl/point_cloud.h>
35 #include <pcl/point_types.h>
36 #include <ros/time.h>
37 #include <ros/publisher.h>
38 
39 namespace rtabmap {
40 class OctoMap;
41 class Memory;
42 class OccupancyGrid;
43 
44 } // namespace rtabmap
45 
46 class MapsManager {
47 public:
48  MapsManager();
49  virtual ~MapsManager();
50  void init(ros::NodeHandle & nh, ros::NodeHandle & pnh, const std::string & name, bool usePublicNamespace);
51  void clear();
52  bool hasSubscribers() const;
53  void backwardCompatibilityParameters(ros::NodeHandle & pnh, rtabmap::ParametersMap & parameters) const;
54  void setParameters(const rtabmap::ParametersMap & parameters);
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);
56 
57  std::map<int, rtabmap::Transform> getFilteredPoses(
58  const std::map<int, rtabmap::Transform> & poses);
59 
60  std::map<int, rtabmap::Transform> updateMapCaches(
61  const std::map<int, rtabmap::Transform> & poses,
62  const rtabmap::Memory * memory,
63  bool updateGrid,
64  bool updateOctomap,
65  const std::map<int, rtabmap::Signature> & signatures = std::map<int, rtabmap::Signature>());
66 
67  void publishMaps(
68  const std::map<int, rtabmap::Transform> & poses,
69  const ros::Time & stamp,
70  const std::string & mapFrameId);
71 
72  cv::Mat getGridMap(
73  float & xMin,
74  float & yMin,
75  float & gridCellSize);
76 
77  cv::Mat getGridProbMap(
78  float & xMin,
79  float & yMin,
80  float & gridCellSize);
81 
82  const rtabmap::OctoMap * getOctomap() const {return octomap_;}
83  const rtabmap::OccupancyGrid * getOccupancyGrid() const {return occupancyGrid_;}
84 
85 private:
86  // mapping stuff
95 
111 
112  std::map<int, rtabmap::Transform> assembledGroundPoses_;
113  std::map<int, rtabmap::Transform> assembledObstaclePoses_;
114  pcl::PointCloud<pcl::PointXYZRGB>::Ptr assembledObstacles_;
115  pcl::PointCloud<pcl::PointXYZRGB>::Ptr assembledGround_;
118  std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr > groundClouds_;
119  std::map<int, pcl::PointCloud<pcl::PointXYZRGB>::Ptr > obstacleClouds_;
120 
121  std::map<int, rtabmap::Transform> gridPoses_;
122  cv::Mat gridMap_;
123  std::map<int, std::pair< std::pair<cv::Mat, cv::Mat>, cv::Mat> > gridMaps_; // < <ground, obstacles>, empty cells >
124  std::map<int, cv::Point3f> gridMapsViewpoints_;
125 
128 
132 
134 
135  bool latching_;
136  std::map<void*, bool> latched_;
137 };
138 
139 #endif /* MAPSMANAGER_H_ */
std::map< int, cv::Point3f > gridMapsViewpoints_
Definition: MapsManager.h:124
int cloudSubtractFilteringMinNeighbors_
Definition: MapsManager.h:89
ros::Publisher octoMapObstacleCloud_
Definition: MapsManager.h:108
std::map< int, rtabmap::Transform > gridPoses_
Definition: MapsManager.h:121
ros::Publisher cloudGroundPub_
Definition: MapsManager.h:97
cv::Mat gridMap_
Definition: MapsManager.h:122
ros::Publisher gridMapPub_
Definition: MapsManager.h:100
rtabmap::OccupancyGrid * occupancyGrid_
Definition: MapsManager.h:126
ros::Publisher scanMapPub_
Definition: MapsManager.h:102
bool cloudOutputVoxelized_
Definition: MapsManager.h:87
std::map< void *, bool > latched_
Definition: MapsManager.h:136
const rtabmap::OctoMap * getOctomap() const
Definition: MapsManager.h:82
ros::Publisher octoMapCloud_
Definition: MapsManager.h:105
std::map< std::string, std::string > ParametersMap
pcl::PointCloud< pcl::PointXYZRGB >::Ptr assembledObstacles_
Definition: MapsManager.h:114
bool alwaysUpdateMap_
Definition: MapsManager.h:93
std::map< int, pcl::PointCloud< pcl::PointXYZRGB >::Ptr > groundClouds_
Definition: MapsManager.h:118
rtabmap::OctoMap * octomap_
Definition: MapsManager.h:129
bool cloudSubtractFiltering_
Definition: MapsManager.h:88
rtabmap::ParametersMap parameters_
Definition: MapsManager.h:133
ros::Publisher octoMapPubFull_
Definition: MapsManager.h:104
ros::Publisher cloudMapPub_
Definition: MapsManager.h:96
ros::Publisher octoMapPubBin_
Definition: MapsManager.h:103
std::map< int, std::pair< std::pair< cv::Mat, cv::Mat >, cv::Mat > > gridMaps_
Definition: MapsManager.h:123
bool latching_
Definition: MapsManager.h:135
rtabmap::FlannIndex assembledGroundIndex_
Definition: MapsManager.h:116
ros::Publisher projMapPub_
Definition: MapsManager.h:99
double mapFilterAngle_
Definition: MapsManager.h:91
const rtabmap::OccupancyGrid * getOccupancyGrid() const
Definition: MapsManager.h:83
rtabmap::FlannIndex assembledObstacleIndex_
Definition: MapsManager.h:117
bool mapCacheCleanup_
Definition: MapsManager.h:92
bool scanEmptyRayTracing_
Definition: MapsManager.h:94
double mapFilterRadius_
Definition: MapsManager.h:90
int octomapTreeDepth_
Definition: MapsManager.h:130
ros::Publisher octoMapEmptySpace_
Definition: MapsManager.h:109
ros::Publisher octoMapFrontierCloud_
Definition: MapsManager.h:106
ros::Publisher octoMapGroundCloud_
Definition: MapsManager.h:107
bool octomapUpdated_
Definition: MapsManager.h:131
std::map< int, pcl::PointCloud< pcl::PointXYZRGB >::Ptr > obstacleClouds_
Definition: MapsManager.h:119
ros::Publisher octoMapProj_
Definition: MapsManager.h:110
bool gridUpdated_
Definition: MapsManager.h:127
pcl::PointCloud< pcl::PointXYZRGB >::Ptr assembledGround_
Definition: MapsManager.h:115
ros::Publisher cloudObstaclesPub_
Definition: MapsManager.h:98
ros::Publisher gridProbMapPub_
Definition: MapsManager.h:101
std::map< int, rtabmap::Transform > assembledGroundPoses_
Definition: MapsManager.h:112
std::map< int, rtabmap::Transform > assembledObstaclePoses_
Definition: MapsManager.h:113


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:42:19