ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
4

Detecting Spheres using RANSAC in PCL

asked 2016-03-21 15:09:35 -0600

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.

image description

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,

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
3

answered 2016-03-24 16:12:38 -0600

I've managed to get to the bottom of this one.

I needed to change,

segmentation.setModelType(pcl::SACMODEL_SPHERE);

to

segmentation.setModelType(pcl::SACMODEL_NORMAL_SPHERE);

RANSAC was still using the basic sphere model, not the sphere with normals. This is picking up sphere's really well now.

edit flag offensive delete link more

Comments

could you share whole code what you have done, I am trying here to detect a cube,

Mahe gravatar image Mahe  ( 2016-10-13 15:28:23 -0600 )edit

Unfortunately a cube in not a simple primitive like a sphere so it can't be detected directly with RANSAC. A cube is effectively 6 faces, with several requirements. 3 pairs must be parallel and equidistant and each face must be a right angles to all others except for it's parallel partner.

PeteBlackerThe3rd gravatar image PeteBlackerThe3rd  ( 2017-09-26 08:47:12 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2016-03-21 15:09:35 -0600

Seen: 4,818 times

Last updated: Mar 24 '16