00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
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
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 && flatSurfaces->size())
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 if(clusteredFlatSurfaces.size())
00099 {
00100 ground = clusteredFlatSurfaces.at(biggestFlatSurfaceIndex);
00101 Eigen::Vector4f min,max;
00102 pcl::getMinMax3D(*cloud, *clusteredFlatSurfaces.at(biggestFlatSurfaceIndex), min, max);
00103
00104 if(maxGroundHeight == 0.0f || min[2] < maxGroundHeight)
00105 {
00106 for(unsigned int i=0; i<clusteredFlatSurfaces.size(); ++i)
00107 {
00108 if((int)i!=biggestFlatSurfaceIndex)
00109 {
00110 Eigen::Vector4f centroid(0,0,0,1);
00111 pcl::compute3DCentroid(*cloud, *clusteredFlatSurfaces.at(i), centroid);
00112 if(maxGroundHeight==0.0f || centroid[2] <= maxGroundHeight || centroid[2] <= max[2])
00113 {
00114 ground = util3d::concatenate(ground, clusteredFlatSurfaces.at(i));
00115 }
00116 else if(flatObstacles)
00117 {
00118 *flatObstacles = util3d::concatenate(*flatObstacles, clusteredFlatSurfaces.at(i));
00119 }
00120 }
00121 }
00122 }
00123 else
00124 {
00125
00126 ground.reset(new std::vector<int>);
00127 if(flatObstacles)
00128 {
00129 *flatObstacles = flatSurfaces;
00130 }
00131 }
00132 }
00133 }
00134 else
00135 {
00136 ground = flatSurfaces;
00137 }
00138
00139 if(ground->size() != cloud->size())
00140 {
00141
00142 pcl::IndicesPtr notObstacles = ground;
00143 if(indices->size())
00144 {
00145 notObstacles = util3d::extractIndices(cloud, indices, true);
00146 notObstacles = util3d::concatenate(notObstacles, ground);
00147 }
00148 pcl::IndicesPtr otherStuffIndices = util3d::extractIndices(cloud, notObstacles, true);
00149
00150
00151 if(maxGroundHeight != 0.0f)
00152 {
00153 otherStuffIndices = rtabmap::util3d::passThrough(cloud, otherStuffIndices, "z", maxGroundHeight, std::numeric_limits<float>::max());
00154 }
00155
00156
00157 if(otherStuffIndices->size())
00158 {
00159 std::vector<pcl::IndicesPtr> clusteredObstaclesSurfaces = util3d::extractClusters(
00160 cloud,
00161 otherStuffIndices,
00162 clusterRadius,
00163 minClusterSize);
00164
00165
00166 obstacles = util3d::concatenate(clusteredObstaclesSurfaces);
00167 }
00168 }
00169 }
00170 }
00171
00172 template<typename PointT>
00173 void segmentObstaclesFromGround(
00174 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00175 pcl::IndicesPtr & ground,
00176 pcl::IndicesPtr & obstacles,
00177 int normalKSearch,
00178 float groundNormalAngle,
00179 float clusterRadius,
00180 int minClusterSize,
00181 bool segmentFlatObstacles,
00182 float maxGroundHeight,
00183 pcl::IndicesPtr * flatObstacles,
00184 const Eigen::Vector4f & viewPoint)
00185 {
00186 pcl::IndicesPtr indices(new std::vector<int>);
00187 segmentObstaclesFromGround<PointT>(
00188 cloud,
00189 indices,
00190 ground,
00191 obstacles,
00192 normalKSearch,
00193 groundNormalAngle,
00194 clusterRadius,
00195 minClusterSize,
00196 segmentFlatObstacles,
00197 maxGroundHeight,
00198 flatObstacles,
00199 viewPoint);
00200 }
00201
00202 template<typename PointT>
00203 void occupancy2DFromGroundObstacles(
00204 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00205 const pcl::IndicesPtr & groundIndices,
00206 const pcl::IndicesPtr & obstaclesIndices,
00207 cv::Mat & ground,
00208 cv::Mat & obstacles,
00209 float cellSize)
00210 {
00211 typename pcl::PointCloud<PointT>::Ptr groundCloud(new pcl::PointCloud<PointT>);
00212 typename pcl::PointCloud<PointT>::Ptr obstaclesCloud(new pcl::PointCloud<PointT>);
00213
00214 if(groundIndices->size())
00215 {
00216 pcl::copyPointCloud(*cloud, *groundIndices, *groundCloud);
00217 }
00218
00219 if(obstaclesIndices->size())
00220 {
00221 pcl::copyPointCloud(*cloud, *obstaclesIndices, *obstaclesCloud);
00222 }
00223
00224 occupancy2DFromGroundObstacles<PointT>(
00225 groundCloud,
00226 obstaclesCloud,
00227 ground,
00228 obstacles,
00229 cellSize);
00230 }
00231
00232 template<typename PointT>
00233 void occupancy2DFromGroundObstacles(
00234 const typename pcl::PointCloud<PointT>::Ptr & groundCloud,
00235 const typename pcl::PointCloud<PointT>::Ptr & obstaclesCloud,
00236 cv::Mat & ground,
00237 cv::Mat & obstacles,
00238 float cellSize)
00239 {
00240 ground = cv::Mat();
00241 if(groundCloud->size())
00242 {
00243
00244 typename pcl::PointCloud<PointT>::Ptr groundCloudProjected;
00245 groundCloudProjected = util3d::projectCloudOnXYPlane(*groundCloud);
00246
00247 groundCloudProjected = util3d::voxelize(groundCloudProjected, cellSize);
00248
00249 ground = cv::Mat(1, (int)groundCloudProjected->size(), CV_32FC2);
00250 for(unsigned int i=0;i<groundCloudProjected->size(); ++i)
00251 {
00252 cv::Vec2f * ptr = ground.ptr<cv::Vec2f>();
00253 ptr[i][0] = groundCloudProjected->at(i).x;
00254 ptr[i][1] = groundCloudProjected->at(i).y;
00255 }
00256 }
00257
00258 obstacles = cv::Mat();
00259 if(obstaclesCloud->size())
00260 {
00261
00262 typename pcl::PointCloud<PointT>::Ptr obstaclesCloudProjected;
00263 obstaclesCloudProjected = util3d::projectCloudOnXYPlane(*obstaclesCloud);
00264
00265 obstaclesCloudProjected = util3d::voxelize(obstaclesCloudProjected, cellSize);
00266
00267 obstacles = cv::Mat(1, (int)obstaclesCloudProjected->size(), CV_32FC2);
00268 for(unsigned int i=0;i<obstaclesCloudProjected->size(); ++i)
00269 {
00270 cv::Vec2f * ptr = obstacles.ptr<cv::Vec2f>();
00271 ptr[i][0] = obstaclesCloudProjected->at(i).x;
00272 ptr[i][1] = obstaclesCloudProjected->at(i).y;
00273 }
00274 }
00275 }
00276
00277 template<typename PointT>
00278 void occupancy2DFromCloud3D(
00279 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00280 const pcl::IndicesPtr & indices,
00281 cv::Mat & ground,
00282 cv::Mat & obstacles,
00283 float cellSize,
00284 float groundNormalAngle,
00285 int minClusterSize,
00286 bool segmentFlatObstacles,
00287 float maxGroundHeight)
00288 {
00289 if(cloud->size() == 0)
00290 {
00291 return;
00292 }
00293 pcl::IndicesPtr groundIndices, obstaclesIndices;
00294
00295 segmentObstaclesFromGround<PointT>(
00296 cloud,
00297 indices,
00298 groundIndices,
00299 obstaclesIndices,
00300 20,
00301 groundNormalAngle,
00302 cellSize*2.0f,
00303 minClusterSize,
00304 segmentFlatObstacles,
00305 maxGroundHeight);
00306
00307 occupancy2DFromGroundObstacles<PointT>(
00308 cloud,
00309 groundIndices,
00310 obstaclesIndices,
00311 ground,
00312 obstacles,
00313 cellSize);
00314 }
00315
00316 template<typename PointT>
00317 void occupancy2DFromCloud3D(
00318 const typename pcl::PointCloud<PointT>::Ptr & cloud,
00319 cv::Mat & ground,
00320 cv::Mat & obstacles,
00321 float cellSize,
00322 float groundNormalAngle,
00323 int minClusterSize,
00324 bool segmentFlatObstacles,
00325 float maxGroundHeight)
00326 {
00327 pcl::IndicesPtr indices(new std::vector<int>);
00328 occupancy2DFromCloud3D<PointT>(cloud, indices, ground, obstacles, cellSize, groundNormalAngle, minClusterSize, segmentFlatObstacles, maxGroundHeight);
00329 }
00330
00331 }
00332 }
00333
00334 #endif