Detecting Spheres using RANSAC in PCL
Hi There,
I've spent a while now trying to setup a robust sphere detection using RANSAC segmentation tools in PCL. The point clouds I'm working with are created by a scanning lidar and I'm trying to detect basket balls at the moment. Here's a picture showing the type of failed sphere detection that is happening most of the time.
I can see how the RANSAC algorithm can make such a false positive when it's working with points alone, so I'm trying to use the point normals as well which I think should prevent these false positives. I've calculated the normals for the point cloud and I'm now using the pcl::SACSegmentationFromNormals object to try the same sphere detection, but it's resulting in exactly the same false positives as before. The only thing I can assume is that for some reason the normals are not being taken into consideration. I've visualized the normals, and they are correctly calculated.
Here's the code I'm using;
ROS_INFO("Polpulating new point cloud");
// generate point cloud for this mesh
scanMesh->populatePointCloud();
boost::shared_ptr<pcl::PointCloud<pcl::PointXYZRGBNormal> > cloud2(scanMesh->cloud);
pcl::ModelCoefficients::Ptr coefficients(new pcl::ModelCoefficients);
pcl::SACSegmentationFromNormals<pcl::PointXYZRGBNormal, pcl::PointXYZRGBNormal> segmentation;
segmentation.setInputCloud(cloud2);
segmentation.setInputNormals(cloud2);
segmentation.setModelType(pcl::SACMODEL_SPHERE);
segmentation.setMethodType(pcl::SAC_RANSAC);
segmentation.setDistanceThreshold(0.01);
segmentation.setOptimizeCoefficients(true);
segmentation.setRadiusLimits(0.1, 0.15);
segmentation.setEpsAngle(15 / (180/3.141592654));
segmentation.setMaxIterations(1000000);
pcl::PointIndices inlierIndices;
segmentation.segment(inlierIndices, *coefficients);
if (inlierIndices.indices.size() == 0)
ROS_INFO("RANSAC nothing found");
else
{
ROS_INFO("RANSAC found shape with [%d] points", (int)inlierIndices.indices.size());
for (int c=0; c<coefficients->values.size(); ++c)
ROS_INFO("Coeff %d = [%f]", (int)c+1, (float)coefficients->values[c]);
// mark the found inliers in green
for (int m=0; m<inlierIndices.indices.size(); ++m)
{
cloud2->points[inlierIndices.indices[m]].r = 0;
cloud2->points[inlierIndices.indices[m]].g = 255;
cloud2->points[inlierIndices.indices[m]].b = 0;
}
}
Does anyone have any experience using the pcl::SACSegmentationFromNormals class for sphere detection?
Thanks,