28 #ifndef UTIL3D_MAPPING_HPP_ 29 #define UTIL3D_MAPPING_HPP_ 33 #include <pcl/common/common.h> 34 #include <pcl/common/centroid.h> 35 #include <pcl/common/io.h> 40 template<
typename Po
intT>
42 const typename pcl::PointCloud<PointT> & cloud)
44 typename pcl::PointCloud<PointT>::Ptr output(
new pcl::PointCloud<PointT>);
46 for(
unsigned int i=0; i<output->size(); ++i)
53 template<
typename Po
intT>
55 const typename pcl::PointCloud<PointT>::Ptr & cloud,
56 const typename pcl::IndicesPtr & indices,
57 pcl::IndicesPtr & ground,
58 pcl::IndicesPtr & obstacles,
60 float groundNormalAngle,
63 bool segmentFlatObstacles,
64 float maxGroundHeight,
65 pcl::IndicesPtr * flatObstacles,
66 const Eigen::Vector4f & viewPoint,
67 float groundNormalsUp)
69 ground.reset(
new std::vector<int>);
70 obstacles.reset(
new std::vector<int>);
73 flatObstacles->reset(
new std::vector<int>);
83 Eigen::Vector4f(0,0,1,0),
88 if(segmentFlatObstacles && flatSurfaces->size())
90 int biggestFlatSurfaceIndex;
97 &biggestFlatSurfaceIndex);
100 if(clusteredFlatSurfaces.size())
102 Eigen::Vector4f biggestSurfaceMin,biggestSurfaceMax;
103 if(maxGroundHeight != 0.0
f)
107 biggestFlatSurfaceIndex = -1;
108 for(
size_t i=0;i<clusteredFlatSurfaces.size();++i)
112 if(min[2]<maxGroundHeight && clusteredFlatSurfaces.at(i)->size() > points)
114 points = clusteredFlatSurfaces.at(i)->size();
115 biggestFlatSurfaceIndex = i;
116 biggestSurfaceMin =
min;
117 biggestSurfaceMax =
max;
123 pcl::getMinMax3D(*cloud, *clusteredFlatSurfaces.at(biggestFlatSurfaceIndex), biggestSurfaceMin, biggestSurfaceMax);
125 if(biggestFlatSurfaceIndex>=0)
127 ground = clusteredFlatSurfaces.at(biggestFlatSurfaceIndex);
130 if(!ground->empty() && (maxGroundHeight == 0.0f || biggestSurfaceMin[2] < maxGroundHeight))
132 for(
unsigned int i=0; i<clusteredFlatSurfaces.size(); ++i)
134 if((
int)i!=biggestFlatSurfaceIndex)
136 Eigen::Vector4f centroid(0,0,0,1);
137 pcl::compute3DCentroid(*cloud, *clusteredFlatSurfaces.at(i), centroid);
138 if(maxGroundHeight==0.0
f || centroid[2] <= maxGroundHeight || centroid[2] <= biggestSurfaceMax[2])
142 else if(flatObstacles)
152 ground.reset(
new std::vector<int>);
155 *flatObstacles = flatSurfaces;
162 ground = flatSurfaces;
165 if(ground->size() != cloud->size())
168 pcl::IndicesPtr notObstacles = ground;
177 if(maxGroundHeight != 0.0
f)
183 if(otherStuffIndices->size())
198 template<
typename Po
intT>
200 const typename pcl::PointCloud<PointT>::Ptr & cloud,
201 pcl::IndicesPtr & ground,
202 pcl::IndicesPtr & obstacles,
204 float groundNormalAngle,
207 bool segmentFlatObstacles,
208 float maxGroundHeight,
209 pcl::IndicesPtr * flatObstacles,
210 const Eigen::Vector4f & viewPoint,
211 float groundNormalsUp)
213 pcl::IndicesPtr indices(
new std::vector<int>);
214 segmentObstaclesFromGround<PointT>(
223 segmentFlatObstacles,
230 template<
typename Po
intT>
232 const typename pcl::PointCloud<PointT>::Ptr & cloud,
233 const pcl::IndicesPtr & groundIndices,
234 const pcl::IndicesPtr & obstaclesIndices,
239 typename pcl::PointCloud<PointT>::Ptr groundCloud(
new pcl::PointCloud<PointT>);
240 typename pcl::PointCloud<PointT>::Ptr obstaclesCloud(
new pcl::PointCloud<PointT>);
242 if(groundIndices->size())
244 pcl::copyPointCloud(*cloud, *groundIndices, *groundCloud);
247 if(obstaclesIndices->size())
249 pcl::copyPointCloud(*cloud, *obstaclesIndices, *obstaclesCloud);
252 occupancy2DFromGroundObstacles<PointT>(
260 template<
typename Po
intT>
262 const typename pcl::PointCloud<PointT>::Ptr & groundCloud,
263 const typename pcl::PointCloud<PointT>::Ptr & obstaclesCloud,
269 if(groundCloud->size())
272 typename pcl::PointCloud<PointT>::Ptr groundCloudProjected;
277 ground = cv::Mat(1, (
int)groundCloudProjected->size(), CV_32FC2);
278 for(
unsigned int i=0;i<groundCloudProjected->size(); ++i)
280 cv::Vec2f * ptr = ground.ptr<cv::Vec2f>();
281 ptr[i][0] = groundCloudProjected->at(i).x;
282 ptr[i][1] = groundCloudProjected->at(i).y;
286 obstacles = cv::Mat();
287 if(obstaclesCloud->size())
290 typename pcl::PointCloud<PointT>::Ptr obstaclesCloudProjected;
293 obstaclesCloudProjected =
util3d::voxelize(obstaclesCloudProjected, cellSize);
295 obstacles = cv::Mat(1, (
int)obstaclesCloudProjected->size(), CV_32FC2);
296 for(
unsigned int i=0;i<obstaclesCloudProjected->size(); ++i)
298 cv::Vec2f * ptr = obstacles.ptr<cv::Vec2f>();
299 ptr[i][0] = obstaclesCloudProjected->at(i).x;
300 ptr[i][1] = obstaclesCloudProjected->at(i).y;
305 template<
typename Po
intT>
307 const typename pcl::PointCloud<PointT>::Ptr & cloud,
308 const pcl::IndicesPtr & indices,
312 float groundNormalAngle,
314 bool segmentFlatObstacles,
315 float maxGroundHeight)
317 if(cloud->size() == 0)
321 pcl::IndicesPtr groundIndices, obstaclesIndices;
323 segmentObstaclesFromGround<PointT>(
332 segmentFlatObstacles,
335 occupancy2DFromGroundObstacles<PointT>(
344 template<
typename Po
intT>
346 const typename pcl::PointCloud<PointT>::Ptr & cloud,
350 float groundNormalAngle,
352 bool segmentFlatObstacles,
353 float maxGroundHeight)
355 pcl::IndicesPtr indices(
new std::vector<int>);
356 occupancy2DFromCloud3D<PointT>(cloud, indices, ground, obstacles, cellSize, groundNormalAngle, minClusterSize, segmentFlatObstacles, maxGroundHeight);
std::vector< pcl::IndicesPtr > RTABMAP_EXP extractClusters(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float clusterTolerance, int minClusterSize, int maxClusterSize=std::numeric_limits< int >::max(), int *biggestClusterIndex=0)
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
pcl::IndicesPtr RTABMAP_EXP passThrough(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, const std::string &axis, float min, float max, bool negative=false)
void RTABMAP_EXP getMinMax3D(const cv::Mat &laserScan, cv::Point3f &min, cv::Point3f &max)
pcl::IndicesPtr RTABMAP_EXP extractIndices(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, bool negative)
pcl::IndicesPtr RTABMAP_EXP normalFiltering(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, float angleMax, const Eigen::Vector4f &normal, int normalKSearch, const Eigen::Vector4f &viewpoint, float groundNormalsUp=0.0f)
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
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 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, float groundNormalsUp)
pcl::IndicesPtr RTABMAP_EXP concatenate(const std::vector< pcl::IndicesPtr > &indices)
Concatenate a vector of indices to a single vector.
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP voxelize(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
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)