OccupancyGrid.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 CORELIB_INCLUDE_RTABMAP_CORE_IMPL_OCCUPANCYGRID_HPP_
00029 #define CORELIB_INCLUDE_RTABMAP_CORE_IMPL_OCCUPANCYGRID_HPP_
00030 
00031 #include <rtabmap/core/util3d_mapping.h>
00032 #include <rtabmap/core/util3d_transforms.h>
00033 #include <rtabmap/utilite/ULogger.h>
00034 
00035 namespace rtabmap {
00036 
00037 template<typename PointT>
00038 typename pcl::PointCloud<PointT>::Ptr OccupancyGrid::segmentCloud(
00039                 const typename pcl::PointCloud<PointT>::Ptr & cloudIn,
00040                 const pcl::IndicesPtr & indicesIn,
00041                 const Transform & pose,
00042                 const cv::Point3f & viewPoint,
00043                 pcl::IndicesPtr & groundIndices,
00044                 pcl::IndicesPtr & obstaclesIndices,
00045                 pcl::IndicesPtr * flatObstacles) const
00046 {
00047         typename pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>);
00048         pcl::IndicesPtr indices(new std::vector<int>);
00049 
00050         if(preVoxelFiltering_)
00051         {
00052                 // voxelize to grid cell size
00053                 cloud = util3d::voxelize(cloudIn, indicesIn, cellSize_);
00054 
00055                 indices->resize(cloud->size());
00056                 for(unsigned int i=0; i<indices->size(); ++i)
00057                 {
00058                         indices->at(i) = i;
00059                 }
00060         }
00061         else
00062         {
00063                 cloud = cloudIn;
00064                 if(indicesIn->empty() && cloud->is_dense)
00065                 {
00066                         indices->resize(cloud->size());
00067                         for(unsigned int i=0; i<indices->size(); ++i)
00068                         {
00069                                 indices->at(i) = i;
00070                         }
00071                 }
00072                 else
00073                 {
00074                         indices = indicesIn;
00075                 }
00076         }
00077 
00078         // add pose rotation without yaw
00079         float roll, pitch, yaw;
00080         pose.getEulerAngles(roll, pitch, yaw);
00081         UDEBUG("node.getPose()=%s projMapFrame_=%d", pose.prettyPrint().c_str(), projMapFrame_?1:0);
00082         cloud = util3d::transformPointCloud(cloud, Transform(0,0, projMapFrame_?pose.z():0, roll, pitch, 0));
00083 
00084         // filter footprint
00085         if(footprintLength_ > 0.0f || footprintWidth_ > 0.0f || footprintHeight_ > 0.0f)
00086         {
00087                 indices = util3d::cropBox(
00088                                 cloud,
00089                                 indices,
00090                                 Eigen::Vector4f(
00091                                                 footprintLength_>0.0f?-footprintLength_/2.0f:std::numeric_limits<int>::min(),
00092                                                 footprintWidth_>0.0f&&footprintLength_>0.0f?-footprintWidth_/2.0f:std::numeric_limits<int>::min(),
00093                                                 0,
00094                                                 1),
00095                                 Eigen::Vector4f(
00096                                                 footprintLength_>0.0f?footprintLength_/2.0f:std::numeric_limits<int>::max(),
00097                                                 footprintWidth_>0.0f&&footprintLength_>0.0f?footprintWidth_/2.0f:std::numeric_limits<int>::max(),
00098                                                 footprintHeight_>0.0f&&footprintLength_>0.0f&&footprintWidth_>0.0f?footprintHeight_:std::numeric_limits<int>::max(),
00099                                                 1),
00100                                 Transform::getIdentity(),
00101                                 true);
00102         }
00103 
00104         // filter ground/obstacles zone
00105         if(minGroundHeight_ != 0.0f || maxObstacleHeight_ != 0.0f)
00106         {
00107                 indices = util3d::passThrough(cloud, indices, "z",
00108                                 minGroundHeight_!=0.0f?minGroundHeight_:std::numeric_limits<int>::min(),
00109                                 maxObstacleHeight_>0.0f?maxObstacleHeight_:std::numeric_limits<int>::max());
00110                 UDEBUG("indices after max obstacles height filtering = %d", (int)indices->size());
00111         }
00112 
00113         if(indices->size())
00114         {
00115                 if(normalsSegmentation_ && !groundIsObstacle_)
00116                 {
00117                         UDEBUG("normalKSearch=%d", normalKSearch_);
00118                         UDEBUG("maxGroundAngle=%f", maxGroundAngle_);
00119                         UDEBUG("Cluster radius=%f", clusterRadius_);
00120                         UDEBUG("flatObstaclesDetected=%d", flatObstaclesDetected_?1:0);
00121                         UDEBUG("maxGroundHeight=%f", maxGroundHeight_);
00122                         util3d::segmentObstaclesFromGround<PointT>(
00123                                         cloud,
00124                                         indices,
00125                                         groundIndices,
00126                                         obstaclesIndices,
00127                                         normalKSearch_,
00128                                         maxGroundAngle_,
00129                                         clusterRadius_,
00130                                         minClusterSize_,
00131                                         flatObstaclesDetected_,
00132                                         maxGroundHeight_,
00133                                         flatObstacles,
00134                                         Eigen::Vector4f(viewPoint.x, viewPoint.y, viewPoint.z+(projMapFrame_?pose.z():0), 1));
00135                         UDEBUG("viewPoint=%f,%f,%f", viewPoint.x, viewPoint.y, viewPoint.z+(projMapFrame_?pose.z():0));
00136                         //UWARN("Saving ground.pcd and obstacles.pcd");
00137                         //pcl::io::savePCDFile("ground.pcd", *cloud, *groundIndices);
00138                         //pcl::io::savePCDFile("obstacles.pcd", *cloud, *obstaclesIndices);
00139                 }
00140                 else
00141                 {
00142                         UDEBUG("");
00143                         // passthrough filter
00144                         groundIndices = rtabmap::util3d::passThrough(cloud, indices, "z",
00145                                         minGroundHeight_!=0.0f?minGroundHeight_:std::numeric_limits<int>::min(),
00146                                         maxGroundHeight_!=0.0f?maxGroundHeight_:std::numeric_limits<int>::max());
00147 
00148                         pcl::IndicesPtr notObstacles = groundIndices;
00149                         if(indices->size())
00150                         {
00151                                 notObstacles = util3d::extractIndices(cloud, indices, true);
00152                                 notObstacles = util3d::concatenate(notObstacles, groundIndices);
00153                         }
00154                         obstaclesIndices = rtabmap::util3d::extractIndices(cloud, notObstacles, true);
00155                 }
00156 
00157                 UDEBUG("groundIndices=%d obstaclesIndices=%d", (int)groundIndices->size(), (int)obstaclesIndices->size());
00158 
00159                 // Do radius filtering after voxel filtering ( a lot faster)
00160                 if(noiseFilteringRadius_ > 0.0 && noiseFilteringMinNeighbors_ > 0)
00161                 {
00162                         UDEBUG("");
00163                         if(groundIndices->size())
00164                         {
00165                                 groundIndices = rtabmap::util3d::radiusFiltering(cloud, groundIndices, noiseFilteringRadius_, noiseFilteringMinNeighbors_);
00166                         }
00167                         if(obstaclesIndices->size())
00168                         {
00169                                 obstaclesIndices = rtabmap::util3d::radiusFiltering(cloud, obstaclesIndices, noiseFilteringRadius_, noiseFilteringMinNeighbors_);
00170                         }
00171                         if(flatObstacles && (*flatObstacles)->size())
00172                         {
00173                                 *flatObstacles = rtabmap::util3d::radiusFiltering(cloud, *flatObstacles, noiseFilteringRadius_, noiseFilteringMinNeighbors_);
00174                         }
00175 
00176                         if(groundIndices->empty() && obstaclesIndices->empty())
00177                         {
00178                                 UWARN("Cloud (with %d points) is empty after noise "
00179                                                 "filtering. Occupancy grid cannot be "
00180                                                 "created.",
00181                                                 (int)cloud->size());
00182 
00183                         }
00184                 }
00185         }
00186         return cloud;
00187 }
00188 
00189 }
00190 
00191 
00192 #endif /* CORELIB_INCLUDE_RTABMAP_CORE_IMPL_OCCUPANCYGRID_HPP_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:21