util3d_mapping.hpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, 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_MAPPING_HPP_
00029 #define UTIL3D_MAPPING_HPP_
00030 
00031 #include <rtabmap/core/util3d_filtering.h>
00032 #include <rtabmap/core/util3d.h>
00033 #include <pcl/common/common.h>
00034 #include <pcl/common/centroid.h>
00035 #include <pcl/common/io.h>
00036 
00037 namespace rtabmap{
00038 namespace util3d{
00039 
00040 template<typename PointT>
00041 typename pcl::PointCloud<PointT>::Ptr projectCloudOnXYPlane(
00042                 const typename pcl::PointCloud<PointT> & cloud)
00043 {
00044         typename pcl::PointCloud<PointT>::Ptr output(new pcl::PointCloud<PointT>);
00045         *output = cloud;
00046         for(unsigned int i=0; i<output->size(); ++i)
00047         {
00048                 output->at(i).z = 0;
00049         }
00050         return output;
00051 }
00052 
00053 template<typename PointT>
00054 void segmentObstaclesFromGround(
00055                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00056                 const typename pcl::IndicesPtr & indices,
00057                 pcl::IndicesPtr & ground,
00058                 pcl::IndicesPtr & obstacles,
00059                 int normalKSearch,
00060                 float groundNormalAngle,
00061                 float clusterRadius,
00062                 int minClusterSize,
00063                 bool segmentFlatObstacles,
00064                 float maxGroundHeight,
00065                 pcl::IndicesPtr * flatObstacles,
00066                 const Eigen::Vector4f & viewPoint)
00067 {
00068         ground.reset(new std::vector<int>);
00069         obstacles.reset(new std::vector<int>);
00070         if(flatObstacles)
00071         {
00072                 flatObstacles->reset(new std::vector<int>);
00073         }
00074 
00075         if(cloud->size())
00076         {
00077                 // Find the ground
00078                 pcl::IndicesPtr flatSurfaces = normalFiltering(
00079                                 cloud,
00080                                 indices,
00081                                 groundNormalAngle,
00082                                 Eigen::Vector4f(0,0,1,0),
00083                                 normalKSearch,
00084                                 viewPoint);
00085 
00086                 if(segmentFlatObstacles)
00087                 {
00088                         int biggestFlatSurfaceIndex;
00089                         std::vector<pcl::IndicesPtr> clusteredFlatSurfaces = extractClusters(
00090                                         cloud,
00091                                         flatSurfaces,
00092                                         clusterRadius,
00093                                         minClusterSize,
00094                                         std::numeric_limits<int>::max(),
00095                                         &biggestFlatSurfaceIndex);
00096 
00097 
00098                         // cluster all surfaces for which the centroid is in the Z-range of the bigger surface
00099                         if(clusteredFlatSurfaces.size())
00100                         {
00101                                 ground = clusteredFlatSurfaces.at(biggestFlatSurfaceIndex);
00102                                 Eigen::Vector4f min,max;
00103                                 pcl::getMinMax3D(*cloud, *clusteredFlatSurfaces.at(biggestFlatSurfaceIndex), min, max);
00104 
00105                                 if(maxGroundHeight <= 0 || min[2] < maxGroundHeight)
00106                                 {
00107                                         for(unsigned int i=0; i<clusteredFlatSurfaces.size(); ++i)
00108                                         {
00109                                                 if((int)i!=biggestFlatSurfaceIndex)
00110                                                 {
00111                                                         Eigen::Vector4f centroid;
00112                                                         pcl::compute3DCentroid(*cloud, *clusteredFlatSurfaces.at(i), centroid);
00113                                                         if(centroid[2] >= min[2]-0.01 &&
00114                                                           (centroid[2] <= max[2]+0.01 || (maxGroundHeight>0 && centroid[2] <= maxGroundHeight+0.01))) // epsilon
00115                                                         {
00116                                                                 ground = util3d::concatenate(ground, clusteredFlatSurfaces.at(i));
00117                                                         }
00118                                                         else if(flatObstacles)
00119                                                         {
00120                                                                 *flatObstacles = util3d::concatenate(*flatObstacles, clusteredFlatSurfaces.at(i));
00121                                                         }
00122                                                 }
00123                                         }
00124                                 }
00125                                 else
00126                                 {
00127                                         // reject ground!
00128                                         ground.reset(new std::vector<int>);
00129                                         if(flatObstacles)
00130                                         {
00131                                                 *flatObstacles = flatSurfaces;
00132                                         }
00133                                 }
00134                         }
00135                 }
00136                 else
00137                 {
00138                         ground = flatSurfaces;
00139                 }
00140 
00141                 if(ground->size() != cloud->size())
00142                 {
00143                         // Remove ground
00144                         pcl::IndicesPtr otherStuffIndices = util3d::extractIndices(cloud, ground, true);
00145 
00146                         // If ground height is set, remove obstacles under it
00147                         if(maxGroundHeight > 0.0f)
00148                         {
00149                                 otherStuffIndices = rtabmap::util3d::passThrough(cloud, otherStuffIndices, "z", maxGroundHeight, std::numeric_limits<float>::max());
00150                         }
00151 
00152                         //Cluster remaining stuff (obstacles)
00153                         if(otherStuffIndices->size())
00154                         {
00155                                 std::vector<pcl::IndicesPtr> clusteredObstaclesSurfaces = util3d::extractClusters(
00156                                                 cloud,
00157                                                 otherStuffIndices,
00158                                                 clusterRadius,
00159                                                 minClusterSize);
00160 
00161                                 // merge indices
00162                                 obstacles = util3d::concatenate(clusteredObstaclesSurfaces);
00163                         }
00164                 }
00165         }
00166 }
00167 
00168 template<typename PointT>
00169 void segmentObstaclesFromGround(
00170                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00171                 pcl::IndicesPtr & ground,
00172                 pcl::IndicesPtr & obstacles,
00173                 int normalKSearch,
00174                 float groundNormalAngle,
00175                 float clusterRadius,
00176                 int minClusterSize,
00177                 bool segmentFlatObstacles,
00178                 float maxGroundHeight,
00179                 pcl::IndicesPtr * flatObstacles,
00180                 const Eigen::Vector4f & viewPoint)
00181 {
00182         pcl::IndicesPtr indices(new std::vector<int>);
00183         segmentObstaclesFromGround<PointT>(
00184                         cloud,
00185                         indices,
00186                         ground,
00187                         obstacles,
00188                         normalKSearch,
00189                         groundNormalAngle,
00190                         clusterRadius,
00191                         minClusterSize,
00192                         segmentFlatObstacles,
00193                         maxGroundHeight,
00194                         flatObstacles,
00195                         viewPoint);
00196 }
00197 
00198 template<typename PointT>
00199 void occupancy2DFromGroundObstacles(
00200                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00201                 const pcl::IndicesPtr & groundIndices,
00202                 const pcl::IndicesPtr & obstaclesIndices,
00203                 cv::Mat & ground,
00204                 cv::Mat & obstacles,
00205                 float cellSize)
00206 {
00207         typename pcl::PointCloud<PointT>::Ptr groundCloud(new pcl::PointCloud<PointT>);
00208         typename pcl::PointCloud<PointT>::Ptr obstaclesCloud(new pcl::PointCloud<PointT>);
00209 
00210         if(groundIndices->size())
00211         {
00212                 pcl::copyPointCloud(*cloud, *groundIndices, *groundCloud);
00213         }
00214 
00215         if(obstaclesIndices->size())
00216         {
00217                 pcl::copyPointCloud(*cloud, *obstaclesIndices, *obstaclesCloud);
00218         }
00219 
00220         occupancy2DFromGroundObstacles<PointT>(
00221                         groundCloud,
00222                         obstaclesCloud,
00223                         ground,
00224                         obstacles,
00225                         cellSize);
00226 }
00227 
00228 template<typename PointT>
00229 void occupancy2DFromGroundObstacles(
00230                 const typename pcl::PointCloud<PointT>::Ptr & groundCloud,
00231                 const typename pcl::PointCloud<PointT>::Ptr & obstaclesCloud,
00232                 cv::Mat & ground,
00233                 cv::Mat & obstacles,
00234                 float cellSize)
00235 {
00236         ground = cv::Mat();
00237         if(groundCloud->size())
00238         {
00239                 //project on XY plane
00240                 typename pcl::PointCloud<PointT>::Ptr groundCloudProjected;
00241                 groundCloudProjected = util3d::projectCloudOnXYPlane(*groundCloud);
00242                 //voxelize to grid cell size
00243                 groundCloudProjected = util3d::voxelize(groundCloudProjected, cellSize);
00244 
00245                 ground = cv::Mat((int)groundCloudProjected->size(), 1, CV_32FC2);
00246                 for(unsigned int i=0;i<groundCloudProjected->size(); ++i)
00247                 {
00248                         ground.at<cv::Vec2f>(i)[0] = groundCloudProjected->at(i).x;
00249                         ground.at<cv::Vec2f>(i)[1] = groundCloudProjected->at(i).y;
00250                 }
00251         }
00252 
00253         obstacles = cv::Mat();
00254         if(obstaclesCloud->size())
00255         {
00256                 //project on XY plane
00257                 typename pcl::PointCloud<PointT>::Ptr obstaclesCloudProjected;
00258                 obstaclesCloudProjected = util3d::projectCloudOnXYPlane(*obstaclesCloud);
00259                 //voxelize to grid cell size
00260                 obstaclesCloudProjected = util3d::voxelize(obstaclesCloudProjected, cellSize);
00261 
00262                 obstacles = cv::Mat((int)obstaclesCloudProjected->size(), 1, CV_32FC2);
00263                 for(unsigned int i=0;i<obstaclesCloudProjected->size(); ++i)
00264                 {
00265                         obstacles.at<cv::Vec2f>(i)[0] = obstaclesCloudProjected->at(i).x;
00266                         obstacles.at<cv::Vec2f>(i)[1] = obstaclesCloudProjected->at(i).y;
00267                 }
00268         }
00269 }
00270 
00271 template<typename PointT>
00272 void occupancy2DFromCloud3D(
00273                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00274                 const pcl::IndicesPtr & indices,
00275                 cv::Mat & ground,
00276                 cv::Mat & obstacles,
00277                 float cellSize,
00278                 float groundNormalAngle,
00279                 int minClusterSize,
00280                 bool segmentFlatObstacles,
00281                 float maxGroundHeight)
00282 {
00283         if(cloud->size() == 0)
00284         {
00285                 return;
00286         }
00287         pcl::IndicesPtr groundIndices, obstaclesIndices;
00288 
00289         segmentObstaclesFromGround<PointT>(
00290                         cloud,
00291                         indices,
00292                         groundIndices,
00293                         obstaclesIndices,
00294                         20,
00295                         groundNormalAngle,
00296                         cellSize*2.0f,
00297                         minClusterSize,
00298                         segmentFlatObstacles,
00299                         maxGroundHeight);
00300 
00301         occupancy2DFromGroundObstacles<PointT>(
00302                         cloud,
00303                         groundIndices,
00304                         obstaclesIndices,
00305                         ground,
00306                         obstacles,
00307                         cellSize);
00308 }
00309 
00310 template<typename PointT>
00311 void occupancy2DFromCloud3D(
00312                 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00313                 cv::Mat & ground,
00314                 cv::Mat & obstacles,
00315                 float cellSize,
00316                 float groundNormalAngle,
00317                 int minClusterSize,
00318                 bool segmentFlatObstacles,
00319                 float maxGroundHeight)
00320 {
00321         pcl::IndicesPtr indices(new std::vector<int>);
00322         occupancy2DFromCloud3D<PointT>(cloud, indices, ground, obstacles, cellSize, groundNormalAngle, minClusterSize, segmentFlatObstacles, maxGroundHeight);
00323 }
00324 
00325 }
00326 }
00327 
00328 #endif /* UTIL3D_MAPPING_HPP_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:28