28 #ifndef UTIL3D_MAPPING_H_ 29 #define UTIL3D_MAPPING_H_ 33 #include <opencv2/core/core.hpp> 36 #include <pcl/pcl_base.h> 37 #include <pcl/point_cloud.h> 38 #include <pcl/point_types.h> 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.");
56 const cv::Point3f & viewpoint,
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.");
64 const cv::Mat & scanHit,
65 const cv::Mat & scanNoHit,
66 const cv::Point3f & viewpoint,
70 bool unknownSpaceFilled =
false,
71 float scanMaxRange = 0.0f);
74 const std::map<int, Transform> & poses,
75 const std::map<
int, std::pair<cv::Mat, cv::Mat> > & occupancy,
79 float minMapSize = 0.0f,
81 float footprintRadius = 0.0f);
84 const std::map<
int, pcl::PointCloud<pcl::PointXYZ>::Ptr > & scans,
86 bool unknownSpaceFilled,
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.");
93 const std::map<
int, pcl::PointCloud<pcl::PointXYZ>::Ptr > & scans,
94 const std::map<int, cv::Point3f > & viewpoints,
96 bool unknownSpaceFilled,
99 float minMapSize = 0.0f,
100 float scanMaxRange = 0.0f),
"Use interface with cv::Mat scans.");
103 const std::map<
int, std::pair<cv::Mat, cv::Mat> > & scans,
104 const std::map<int, cv::Point3f > & viewpoints,
106 bool unknownSpaceFilled,
109 float minMapSize = 0.0f,
110 float scanMaxRange = 0.0f);
113 const cv::Point2i & end,
115 bool stopOnObstacle);
122 template<
typename Po
intT>
124 const typename pcl::PointCloud<PointT> & cloud);
127 template<
typename Po
intT>
129 const typename pcl::PointCloud<PointT>::Ptr & cloud,
130 const pcl::IndicesPtr & indices,
131 pcl::IndicesPtr & ground,
132 pcl::IndicesPtr & obstacles,
134 float groundNormalAngle,
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 Po
intT>
143 const typename pcl::PointCloud<PointT>::Ptr & cloud,
144 pcl::IndicesPtr & ground,
145 pcl::IndicesPtr & obstacles,
147 float groundNormalAngle,
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));
155 template<
typename Po
intT>
157 const typename pcl::PointCloud<PointT>::Ptr & cloud,
158 const pcl::IndicesPtr & groundIndices,
159 const pcl::IndicesPtr & obstaclesIndices,
164 template<
typename Po
intT>
166 const typename pcl::PointCloud<PointT>::Ptr & groundCloud,
167 const typename pcl::PointCloud<PointT>::Ptr & obstaclesCloud,
172 template<
typename Po
intT>
174 const typename pcl::PointCloud<PointT>::Ptr & cloud,
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 Po
intT>
184 const typename pcl::PointCloud<PointT>::Ptr & cloud,
185 const pcl::IndicesPtr & indices,
188 float cellSize = 0.05f,
189 float groundNormalAngle = M_PI_4,
190 int minClusterSize = 20,
191 bool segmentFlatObstacles =
false,
192 float maxGroundHeight = 0.0f);
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)
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)