util3d.hpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #ifndef UTIL3D_HPP_
00029 #define UTIL3D_HPP_
00030 
00031 #include <rtabmap/utilite/ULogger.h>
00032 #include <pcl/filters/voxel_grid.h>
00033 #include <pcl/filters/random_sample.h>
00034 #include <pcl/filters/passthrough.h>
00035 #include <pcl/filters/filter.h>
00036 #include <pcl/filters/extract_indices.h>
00037 #include <pcl/common/transforms.h>
00038 #include <pcl/common/common.h>
00039 #include <pcl/search/kdtree.h>
00040 #include <pcl/features/normal_3d.h>
00041 #include <pcl/segmentation/extract_clusters.h>
00042 
00043 namespace rtabmap{
00044 namespace util3d{
00045 
00046 template<typename PointT>
00047 typename pcl::PointCloud<PointT>::Ptr voxelize(
00048                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00049                 float voxelSize)
00050 {
00051         typedef typename pcl::PointCloud<PointT> PointCloud;
00052         typedef typename PointCloud::Ptr PointCloudPtr;
00053         UASSERT(voxelSize > 0.0f);
00054         PointCloudPtr output(new PointCloud);
00055         pcl::VoxelGrid<PointT> filter;
00056         filter.setLeafSize(voxelSize, voxelSize, voxelSize);
00057         filter.setInputCloud(cloud);
00058         filter.filter(*output);
00059         return output;
00060 }
00061 
00062 template<typename PointT>
00063 typename pcl::PointCloud<PointT>::Ptr sampling(
00064                 const typename pcl::PointCloud<PointT>::Ptr & cloud, int samples)
00065 {
00066         typedef typename pcl::PointCloud<PointT> PointCloud;
00067         typedef typename PointCloud::Ptr PointCloudPtr;
00068         UASSERT(samples > 0);
00069         PointCloudPtr output(new PointCloud);
00070         pcl::RandomSample<PointT> filter;
00071         filter.setSample(samples);
00072         filter.setInputCloud(cloud);
00073         filter.filter(*output);
00074         return output;
00075 }
00076 
00077 template<typename PointT>
00078 typename pcl::PointCloud<PointT>::Ptr passThrough(
00079                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00080                 const std::string & axis,
00081                 float min,
00082                 float max)
00083 {
00084         typedef typename pcl::PointCloud<PointT> PointCloud;
00085         typedef typename PointCloud::Ptr PointCloudPtr;
00086         UASSERT(max > min);
00087         UASSERT(axis.compare("x") == 0 || axis.compare("y") == 0 || axis.compare("z") == 0);
00088 
00089         PointCloudPtr output(new PointCloud);
00090         pcl::PassThrough<PointT> filter;
00091         filter.setFilterFieldName(axis);
00092         filter.setFilterLimits(min, max);
00093         filter.setInputCloud(cloud);
00094         filter.filter(*output);
00095         return output;
00096 }
00097 
00098 template<typename PointT>
00099 typename pcl::PointCloud<PointT>::Ptr removeNaNFromPointCloud(
00100                 const typename pcl::PointCloud<PointT>::Ptr & cloud)
00101 {
00102         typedef typename pcl::PointCloud<PointT> PointCloud;
00103         typedef typename PointCloud::Ptr PointCloudPtr;
00104         PointCloudPtr output(new PointCloud);
00105         std::vector<int> indices;
00106         pcl::removeNaNFromPointCloud<PointT>(*cloud, *output, indices);
00107         return output;
00108 }
00109 
00110 template<typename PointT>
00111 typename pcl::PointCloud<PointT>::Ptr removeNaNNormalsFromPointCloud(
00112                 const typename pcl::PointCloud<PointT>::Ptr & cloud)
00113 {
00114         typedef typename pcl::PointCloud<PointT> PointCloud;
00115         typedef typename PointCloud::Ptr PointCloudPtr;
00116         PointCloudPtr output(new PointCloud);
00117         std::vector<int> indices;
00118         pcl::removeNaNNormalsFromPointCloud<PointT>(*cloud, *output, indices);
00119         return output;
00120 }
00121 
00122 template<typename PointT>
00123 typename pcl::PointCloud<PointT>::Ptr transformPointCloud(
00124                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00125                 const Transform & transform)
00126 {
00127         typedef typename pcl::PointCloud<PointT> PointCloud;
00128         typedef typename PointCloud::Ptr PointCloudPtr;
00129         PointCloudPtr output(new PointCloud);
00130         pcl::transformPointCloud<PointT>(*cloud, *output, transform.toEigen4f());
00131         return output;
00132 }
00133 
00134 template<typename PointT>
00135 PointT transformPoint(
00136                 const PointT & pt,
00137                 const Transform & transform)
00138 {
00139         return pcl::transformPoint(pt, transform.toEigen3f());
00140 }
00141 
00142 template<typename PointT>
00143 void segmentObstaclesFromGround(
00144                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00145                 pcl::IndicesPtr & ground,
00146                 pcl::IndicesPtr & obstacles,
00147                 float normalRadiusSearch,
00148                 float groundNormalAngle,
00149                 int minClusterSize,
00150                 bool segmentFlatObstacles)
00151 {
00152         ground.reset(new std::vector<int>);
00153         obstacles.reset(new std::vector<int>);
00154 
00155         if(cloud->size())
00156         {
00157                 // Find the ground
00158                 pcl::IndicesPtr flatSurfaces = util3d::normalFiltering<PointT>(
00159                                 cloud,
00160                                 groundNormalAngle,
00161                                 Eigen::Vector4f(0,0,1,0),
00162                                 normalRadiusSearch*2.0f,
00163                                 Eigen::Vector4f(0,0,100,0));
00164 
00165                 if(segmentFlatObstacles)
00166                 {
00167                         int biggestFlatSurfaceIndex;
00168                         std::vector<pcl::IndicesPtr> clusteredFlatSurfaces = util3d::extractClusters<PointT>(
00169                                         cloud,
00170                                         flatSurfaces,
00171                                         normalRadiusSearch*2.0f,
00172                                         minClusterSize,
00173                                         std::numeric_limits<int>::max(),
00174                                         &biggestFlatSurfaceIndex);
00175 
00176 
00177                         // cluster all surfaces for which the centroid is in the Z-range of the bigger surface
00178                         ground = clusteredFlatSurfaces.at(biggestFlatSurfaceIndex);
00179                         Eigen::Vector4f min,max;
00180                         pcl::getMinMax3D<PointT>(*cloud, *clusteredFlatSurfaces.at(biggestFlatSurfaceIndex), min, max);
00181 
00182                         for(unsigned int i=0; i<clusteredFlatSurfaces.size(); ++i)
00183                         {
00184                                 if((int)i!=biggestFlatSurfaceIndex)
00185                                 {
00186                                         Eigen::Vector4f centroid;
00187                                         pcl::compute3DCentroid<PointT>(*cloud, *clusteredFlatSurfaces.at(i), centroid);
00188                                         if(centroid[2] >= min[2] && centroid[2] <= max[2])
00189                                         {
00190                                                 ground = util3d::concatenate(ground, clusteredFlatSurfaces.at(i));
00191                                         }
00192                                 }
00193                         }
00194                 }
00195                 else
00196                 {
00197                         ground = flatSurfaces;
00198                 }
00199 
00200                 if(ground->size() != cloud->size())
00201                 {
00202                         // Remove ground
00203                         pcl::IndicesPtr otherStuffIndices = util3d::extractNegativeIndices<PointT>(cloud, ground);
00204 
00205                         //Cluster remaining stuff (obstacles)
00206                         std::vector<pcl::IndicesPtr> clusteredObstaclesSurfaces = util3d::extractClusters<PointT>(
00207                                         cloud,
00208                                         otherStuffIndices,
00209                                         normalRadiusSearch*2.0f,
00210                                         minClusterSize);
00211 
00212                         // merge indices
00213                         obstacles = util3d::concatenate(clusteredObstaclesSurfaces);
00214                 }
00215         }
00216 }
00217 
00218 template<typename PointT>
00219 void projectCloudOnXYPlane(
00220                 typename pcl::PointCloud<PointT>::Ptr & cloud)
00221 {
00222         for(unsigned int i=0; i<cloud->size(); ++i)
00223         {
00224                 cloud->at(i).z = 0;
00225         }
00226 }
00227 
00228 template<typename PointT>
00229 pcl::IndicesPtr radiusFiltering(
00230                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00231                 float radiusSearch,
00232                 int minNeighborsInRadius)
00233 {
00234         pcl::IndicesPtr indices(new std::vector<int>);
00235         return radiusFiltering<PointT>(cloud, indices, radiusSearch, minNeighborsInRadius);
00236 }
00237 
00238 template<typename PointT>
00239 pcl::IndicesPtr radiusFiltering(
00240                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00241                 const pcl::IndicesPtr & indices,
00242                 float radiusSearch,
00243                 int minNeighborsInRadius)
00244 {
00245         typedef typename pcl::search::KdTree<PointT> KdTree;
00246         typedef typename KdTree::Ptr KdTreePtr;
00247         KdTreePtr tree (new KdTree(false));
00248 
00249         if(indices->size())
00250         {
00251                 pcl::IndicesPtr output(new std::vector<int>(indices->size()));
00252                 int oi = 0; // output iterator
00253                 tree->setInputCloud(cloud, indices);
00254                 for(unsigned int i=0; i<indices->size(); ++i)
00255                 {
00256                         std::vector<int> kIndices;
00257                         std::vector<float> kDistances;
00258                         int k = tree->radiusSearch(cloud->at(indices->at(i)), radiusSearch, kIndices, kDistances);
00259                         if(k > minNeighborsInRadius)
00260                         {
00261                                 output->at(oi++) = indices->at(i);
00262                         }
00263                 }
00264                 output->resize(oi);
00265                 return output;
00266         }
00267         else
00268         {
00269                 pcl::IndicesPtr output(new std::vector<int>(cloud->size()));
00270                 int oi = 0; // output iterator
00271                 tree->setInputCloud(cloud);
00272                 for(unsigned int i=0; i<cloud->size(); ++i)
00273                 {
00274                         std::vector<int> kIndices;
00275                         std::vector<float> kDistances;
00276                         int k = tree->radiusSearch(cloud->at(i), radiusSearch, kIndices, kDistances);
00277                         if(k > minNeighborsInRadius)
00278                         {
00279                                 output->at(oi++) = i;
00280                         }
00281                 }
00282                 output->resize(oi);
00283                 return output;
00284         }
00285 }
00286 
00287 template<typename PointT>
00288 pcl::IndicesPtr normalFiltering(
00289                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00290                 float angleMax,
00291                 const Eigen::Vector4f & normal,
00292                 float radiusSearch,
00293                 const Eigen::Vector4f & viewpoint)
00294 {
00295         pcl::IndicesPtr indices(new std::vector<int>);
00296         return normalFiltering<PointT>(cloud, indices, angleMax, normal, radiusSearch, viewpoint);
00297 }
00298 
00299 template<typename PointT>
00300 pcl::IndicesPtr normalFiltering(
00301                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00302                 const pcl::IndicesPtr & indices,
00303                 float angleMax,
00304                 const Eigen::Vector4f & normal,
00305                 float radiusSearch,
00306                 const Eigen::Vector4f & viewpoint)
00307 {
00308         pcl::IndicesPtr output(new std::vector<int>());
00309 
00310         if(cloud->size())
00311         {
00312                 typedef typename pcl::search::KdTree<PointT> KdTree;
00313                 typedef typename KdTree::Ptr KdTreePtr;
00314 
00315                 pcl::NormalEstimation<PointT, pcl::Normal> ne;
00316                 ne.setInputCloud (cloud);
00317                 if(indices->size())
00318                 {
00319                         ne.setIndices(indices);
00320                 }
00321 
00322                 KdTreePtr tree (new KdTree(false));
00323 
00324                 if(indices->size())
00325                 {
00326                         tree->setInputCloud(cloud, indices);
00327                 }
00328                 else
00329                 {
00330                         tree->setInputCloud(cloud);
00331                 }
00332                 ne.setSearchMethod (tree);
00333 
00334                 pcl::PointCloud<pcl::Normal>::Ptr cloud_normals (new pcl::PointCloud<pcl::Normal>);
00335 
00336                 ne.setRadiusSearch (radiusSearch);
00337                 if(viewpoint[0] != 0 || viewpoint[1] != 0 || viewpoint[2] != 0)
00338                 {
00339                         ne.setViewPoint(viewpoint[0], viewpoint[1], viewpoint[2]);
00340                 }
00341 
00342                 ne.compute (*cloud_normals);
00343 
00344                 output->resize(cloud_normals->size());
00345                 int oi = 0; // output iterator
00346                 Eigen::Vector3f n(normal[0], normal[1], normal[2]);
00347                 for(unsigned int i=0; i<cloud_normals->size(); ++i)
00348                 {
00349                         Eigen::Vector4f v(cloud_normals->at(i).normal_x, cloud_normals->at(i).normal_y, cloud_normals->at(i).normal_z, 0.0f);
00350                         float angle = pcl::getAngle3D(normal, v);
00351                         if(angle < angleMax)
00352                         {
00353                                 output->at(oi++) = indices->size()!=0?indices->at(i):i;
00354                         }
00355                 }
00356                 output->resize(oi);
00357         }
00358 
00359         return output;
00360 }
00361 
00362 template<typename PointT>
00363 std::vector<pcl::IndicesPtr> extractClusters(
00364                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00365                 float clusterTolerance,
00366                 int minClusterSize,
00367                 int maxClusterSize,
00368                 int * biggestClusterIndex)
00369 {
00370         pcl::IndicesPtr indices(new std::vector<int>);
00371         return extractClusters<PointT>(cloud, indices, clusterTolerance, minClusterSize, maxClusterSize, biggestClusterIndex);
00372 }
00373 
00374 template<typename PointT>
00375 std::vector<pcl::IndicesPtr> extractClusters(
00376                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00377                 const pcl::IndicesPtr & indices,
00378                 float clusterTolerance,
00379                 int minClusterSize,
00380                 int maxClusterSize,
00381                 int * biggestClusterIndex)
00382 {
00383         typedef typename pcl::search::KdTree<PointT> KdTree;
00384         typedef typename KdTree::Ptr KdTreePtr;
00385 
00386         KdTreePtr tree(new KdTree);
00387         pcl::EuclideanClusterExtraction<PointT> ec;
00388         ec.setClusterTolerance (clusterTolerance);
00389         ec.setMinClusterSize (minClusterSize);
00390         ec.setMaxClusterSize (maxClusterSize);
00391         ec.setInputCloud (cloud);
00392 
00393         if(indices->size())
00394         {
00395                 ec.setIndices(indices);
00396                 tree->setInputCloud(cloud, indices);
00397         }
00398         else
00399         {
00400                 tree->setInputCloud(cloud);
00401         }
00402         ec.setSearchMethod (tree);
00403 
00404         std::vector<pcl::PointIndices> cluster_indices;
00405         ec.extract (cluster_indices);
00406 
00407         int maxIndex=-1;
00408         unsigned int maxSize = 0;
00409         std::vector<pcl::IndicesPtr> output(cluster_indices.size());
00410         for(unsigned int i=0; i<cluster_indices.size(); ++i)
00411         {
00412                 output[i] = pcl::IndicesPtr(new std::vector<int>(cluster_indices[i].indices));
00413 
00414                 if(maxSize < cluster_indices[i].indices.size())
00415                 {
00416                         maxSize = (unsigned int)cluster_indices[i].indices.size();
00417                         maxIndex = i;
00418                 }
00419         }
00420         if(biggestClusterIndex)
00421         {
00422                 *biggestClusterIndex = maxIndex;
00423         }
00424 
00425         return output;
00426 }
00427 
00428 template<typename PointT>
00429 pcl::IndicesPtr extractNegativeIndices(
00430                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00431                 const pcl::IndicesPtr & indices)
00432 {
00433         pcl::IndicesPtr output(new std::vector<int>);
00434         pcl::ExtractIndices<PointT> extract;
00435         extract.setInputCloud (cloud);
00436         extract.setIndices(indices);
00437         extract.setNegative(true);
00438         extract.filter(*output);
00439         return output;
00440 }
00441 
00442 template<typename PointT>
00443 void occupancy2DFromCloud3D(
00444                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00445                 cv::Mat & ground,
00446                 cv::Mat & obstacles,
00447                 float cellSize,
00448                 float groundNormalAngle,
00449                 int minClusterSize)
00450 {
00451         if(cloud->size() == 0)
00452         {
00453                 return;
00454         }
00455         pcl::IndicesPtr groundIndices, obstaclesIndices;
00456 
00457         segmentObstaclesFromGround<PointT>(cloud,
00458                         groundIndices,
00459                         obstaclesIndices,
00460                         cellSize,
00461                         groundNormalAngle,
00462                         minClusterSize);
00463 
00464         pcl::PointCloud<pcl::PointXYZ>::Ptr groundCloud(new pcl::PointCloud<pcl::PointXYZ>);
00465         pcl::PointCloud<pcl::PointXYZ>::Ptr obstaclesCloud(new pcl::PointCloud<pcl::PointXYZ>);
00466 
00467         if(groundIndices->size())
00468         {
00469                 pcl::copyPointCloud(*cloud, *groundIndices, *groundCloud);
00470                 //project on XY plane
00471                 util3d::projectCloudOnXYPlane<pcl::PointXYZ>(groundCloud);
00472                 //voxelize to grid cell size
00473                 groundCloud = util3d::voxelize<pcl::PointXYZ>(groundCloud, cellSize);
00474         }
00475 
00476         if(obstaclesIndices->size())
00477         {
00478                 pcl::copyPointCloud(*cloud, *obstaclesIndices, *obstaclesCloud);
00479                 //project on XY plane
00480                 util3d::projectCloudOnXYPlane<pcl::PointXYZ>(obstaclesCloud);
00481                 //voxelize to grid cell size
00482                 obstaclesCloud = util3d::voxelize<pcl::PointXYZ>(obstaclesCloud, cellSize);
00483         }
00484 
00485         ground = cv::Mat();
00486         if(groundCloud->size())
00487         {
00488                 ground = cv::Mat((int)groundCloud->size(), 1, CV_32FC2);
00489                 for(unsigned int i=0;i<groundCloud->size(); ++i)
00490                 {
00491                         ground.at<cv::Vec2f>(i)[0] = groundCloud->at(i).x;
00492                         ground.at<cv::Vec2f>(i)[1] = groundCloud->at(i).y;
00493                 }
00494         }
00495 
00496         obstacles = cv::Mat();
00497         if(obstaclesCloud->size())
00498         {
00499                 obstacles = cv::Mat((int)obstaclesCloud->size(), 1, CV_32FC2);
00500                 for(unsigned int i=0;i<obstaclesCloud->size(); ++i)
00501                 {
00502                         obstacles.at<cv::Vec2f>(i)[0] = obstaclesCloud->at(i).x;
00503                         obstacles.at<cv::Vec2f>(i)[1] = obstaclesCloud->at(i).y;
00504                 }
00505         }
00506 }
00507 
00508 } // util3d
00509 } // rtabmap
00510 #endif //UTIL3D_HPP_


rtabmap
Author(s): Mathieu Labbe
autogenerated on Fri Aug 28 2015 12:51:42