util3d_mapping.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 UTIL3D_MAPPING_H_
29 #define UTIL3D_MAPPING_H_
30 
32 
33 #include <opencv2/core/core.hpp>
34 #include <map>
35 #include <rtabmap/core/Transform.h>
36 #include <pcl/pcl_base.h>
37 #include <pcl/point_cloud.h>
38 #include <pcl/point_types.h>
39 
40 namespace rtabmap
41 {
42 
43 namespace util3d
44 {
45 
47  const cv::Mat & scan, // in /base_link frame
48  cv::Mat & empty,
49  cv::Mat & occupied,
50  float cellSize,
51  bool unknownSpaceFilled = false,
52  float scanMaxRange = 0.0f), "Use interface with \"viewpoint\" parameter to make sure the ray tracing origin is from the sensor and not the base.");
53 
55  const cv::Mat & scan, // in /base_link frame
56  const cv::Point3f & viewpoint, // /base_link -> /base_scan
57  cv::Mat & empty,
58  cv::Mat & occupied,
59  float cellSize,
60  bool unknownSpaceFilled = false,
61  float scanMaxRange = 0.0f), "Use interface with scanHit/scanNoHit parameters: scanNoHit set to null matrix has the same functionality than this method.");
62 
64  const cv::Mat & scanHit, // in /base_link frame
65  const cv::Mat & scanNoHit, // in /base_link frame
66  const cv::Point3f & viewpoint, // /base_link -> /base_scan
67  cv::Mat & empty,
68  cv::Mat & occupied,
69  float cellSize,
70  bool unknownSpaceFilled = false,
71  float scanMaxRange = 0.0f); // would be set if unknownSpaceFilled=true
72 
74  const std::map<int, Transform> & poses,
75  const std::map<int, std::pair<cv::Mat, cv::Mat> > & occupancy,
76  float cellSize,
77  float & xMin,
78  float & yMin,
79  float minMapSize = 0.0f,
80  bool erode = false,
81  float footprintRadius = 0.0f);
82 
83 RTABMAP_DEPRECATED(cv::Mat RTABMAP_EXP create2DMap(const std::map<int, Transform> & poses,
84  const std::map<int, pcl::PointCloud<pcl::PointXYZ>::Ptr > & scans, // in /base_link frame
85  float cellSize,
86  bool unknownSpaceFilled,
87  float & xMin,
88  float & yMin,
89  float minMapSize = 0.0f,
90  float scanMaxRange = 0.0f), "Use interface with \"viewpoints\" parameter to make sure the ray tracing origin is from the sensor and not the base.");
91 
92 RTABMAP_DEPRECATED(cv::Mat RTABMAP_EXP create2DMap(const std::map<int, Transform> & poses,
93  const std::map<int, pcl::PointCloud<pcl::PointXYZ>::Ptr > & scans, // in /base_link frame
94  const std::map<int, cv::Point3f > & viewpoints, // /base_link -> /base_scan
95  float cellSize,
96  bool unknownSpaceFilled,
97  float & xMin,
98  float & yMin,
99  float minMapSize = 0.0f,
100  float scanMaxRange = 0.0f), "Use interface with cv::Mat scans.");
101 
102 cv::Mat RTABMAP_EXP create2DMap(const std::map<int, Transform> & poses,
103  const std::map<int, std::pair<cv::Mat, cv::Mat> > & scans, // <id, <hit, no hit> >, in /base_link frame
104  const std::map<int, cv::Point3f > & viewpoints, // /base_link -> /base_scan
105  float cellSize,
106  bool unknownSpaceFilled,
107  float & xMin,
108  float & yMin,
109  float minMapSize = 0.0f,
110  float scanMaxRange = 0.0f); // would be set if unknownSpaceFilled=true
111 
112 void RTABMAP_EXP rayTrace(const cv::Point2i & start,
113  const cv::Point2i & end,
114  cv::Mat & grid,
115  bool stopOnObstacle);
116 
117 cv::Mat RTABMAP_EXP convertMap2Image8U(const cv::Mat & map8S, bool pgmFormat = false);
118 cv::Mat RTABMAP_EXP convertImage8U2Map(const cv::Mat & map8U, bool pgmFormat = false);
119 
120 cv::Mat RTABMAP_EXP erodeMap(const cv::Mat & map);
121 
122 template<typename PointT>
123 typename pcl::PointCloud<PointT>::Ptr projectCloudOnXYPlane(
124  const typename pcl::PointCloud<PointT> & cloud);
125 
126 // templated methods
127 template<typename PointT>
129  const typename pcl::PointCloud<PointT>::Ptr & cloud,
130  const pcl::IndicesPtr & indices,
131  pcl::IndicesPtr & ground,
132  pcl::IndicesPtr & obstacles,
133  int normalKSearch,
134  float groundNormalAngle,
135  float clusterRadius,
136  int minClusterSize,
137  bool segmentFlatObstacles = false,
138  float maxGroundHeight = 0.0f,
139  pcl::IndicesPtr * flatObstacles = 0,
140  const Eigen::Vector4f & viewPoint = Eigen::Vector4f(0,0,100,0));
141 template<typename PointT>
143  const typename pcl::PointCloud<PointT>::Ptr & cloud,
144  pcl::IndicesPtr & ground,
145  pcl::IndicesPtr & obstacles,
146  int normalKSearch,
147  float groundNormalAngle,
148  float clusterRadius,
149  int minClusterSize,
150  bool segmentFlatObstacles = false,
151  float maxGroundHeight = 0.0f,
152  pcl::IndicesPtr * flatObstacles = 0,
153  const Eigen::Vector4f & viewPoint = Eigen::Vector4f(0,0,100,0));
154 
155 template<typename PointT>
157  const typename pcl::PointCloud<PointT>::Ptr & cloud,
158  const pcl::IndicesPtr & groundIndices,
159  const pcl::IndicesPtr & obstaclesIndices,
160  cv::Mat & ground,
161  cv::Mat & obstacles,
162  float cellSize);
163 
164 template<typename PointT>
166  const typename pcl::PointCloud<PointT>::Ptr & groundCloud,
167  const typename pcl::PointCloud<PointT>::Ptr & obstaclesCloud,
168  cv::Mat & ground,
169  cv::Mat & obstacles,
170  float cellSize);
171 
172 template<typename PointT>
174  const typename pcl::PointCloud<PointT>::Ptr & cloud,
175  cv::Mat & ground,
176  cv::Mat & obstacles,
177  float cellSize = 0.05f,
178  float groundNormalAngle = M_PI_4,
179  int minClusterSize = 20,
180  bool segmentFlatObstacles = false,
181  float maxGroundHeight = 0.0f);
182 template<typename PointT>
184  const typename pcl::PointCloud<PointT>::Ptr & cloud,
185  const pcl::IndicesPtr & indices,
186  cv::Mat & ground,
187  cv::Mat & obstacles,
188  float cellSize = 0.05f,
189  float groundNormalAngle = M_PI_4,
190  int minClusterSize = 20,
191  bool segmentFlatObstacles = false,
192  float maxGroundHeight = 0.0f);
193 
194 } // namespace util3d
195 } // namespace rtabmap
196 
198 
199 #endif /* UTIL3D_MAPPING_H_ */
cv::Mat RTABMAP_EXP erodeMap(const cv::Mat &map)
cv::Mat RTABMAP_EXP create2DMapFromOccupancyLocalMaps(const std::map< int, Transform > &poses, const std::map< int, std::pair< cv::Mat, cv::Mat > > &occupancy, float cellSize, float &xMin, float &yMin, float minMapSize=0.0f, bool erode=false, float footprintRadius=0.0f)
cv::Mat RTABMAP_EXP create2DMap(const std::map< int, Transform > &poses, const std::map< int, std::pair< cv::Mat, cv::Mat > > &scans, const std::map< int, cv::Point3f > &viewpoints, float cellSize, bool unknownSpaceFilled, float &xMin, float &yMin, float minMapSize=0.0f, float scanMaxRange=0.0f)
void RTABMAP_EXP occupancy2DFromLaserScan(const cv::Mat &scanHit, const cv::Mat &scanNoHit, const cv::Point3f &viewpoint, cv::Mat &empty, cv::Mat &occupied, float cellSize, bool unknownSpaceFilled=false, float scanMaxRange=0.0f)
#define RTABMAP_EXP
Definition: RtabmapExp.h:38
RTABMAP_DEPRECATED(pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP cloudFromDepth(const cv::Mat &imageDepth, float cx, float cy, float fx, float fy, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0),"Use cloudFromDepth with CameraModel interface.")
cv::Mat RTABMAP_EXP convertImage8U2Map(const cv::Mat &map8U, bool pgmFormat=false)
cv::Mat RTABMAP_EXP convertMap2Image8U(const cv::Mat &map8S, bool pgmFormat=false)
void segmentObstaclesFromGround(const typename pcl::PointCloud< PointT >::Ptr &cloud, const typename pcl::IndicesPtr &indices, pcl::IndicesPtr &ground, pcl::IndicesPtr &obstacles, int normalKSearch, float groundNormalAngle, float clusterRadius, int minClusterSize, bool segmentFlatObstacles, float maxGroundHeight, pcl::IndicesPtr *flatObstacles, const Eigen::Vector4f &viewPoint)
void occupancy2DFromCloud3D(const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &indices, cv::Mat &ground, cv::Mat &obstacles, float cellSize, float groundNormalAngle, int minClusterSize, bool segmentFlatObstacles, float maxGroundHeight)
void RTABMAP_EXP rayTrace(const cv::Point2i &start, const cv::Point2i &end, cv::Mat &grid, bool stopOnObstacle)
pcl::PointCloud< PointT >::Ptr projectCloudOnXYPlane(const typename pcl::PointCloud< PointT > &cloud)
void occupancy2DFromGroundObstacles(const typename pcl::PointCloud< PointT >::Ptr &cloud, const pcl::IndicesPtr &groundIndices, const pcl::IndicesPtr &obstaclesIndices, cv::Mat &ground, cv::Mat &obstacles, float cellSize)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:43:41