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

PCL IterativeClosestPoint unable to find nearest neighbour

asked 2011-08-08 21:39:07 -0600

updated 2011-08-14 16:55:42 -0600

kwc gravatar image

I'm using the RGBDSLAM from http://www.ros.org/wiki/rgbdslam to create a map with my Kinect. The general ICP implementation provided is a bit buggy so I wanted to replace that with the ICP from PCL. Used the tutorial and everything compiles fine. But when executed the ICP does not converge but outputs this error message:

[pcl::IterativeClosestPoint::computeTransformation] Unable to find a nearest neighbour in the target dataset for point 3 in the source!

I'd like to narrow down the cause for this, so if anyone has any experience with the parameters of the PCL ICP, I'd really appreciate if you share them! Just so I have an idea what parameters should work for this scenario. If I can rule out wrong parameters (especially max iterations and distance) I can dig into the pointclouds themselves to see if I am somehow messing up target and input cloud or have the wrong transformations or whatever.

I'm using ROS diamondback on Ubuntu 10.10 32bit with the provided PCL.

UPDATE: I tried several sets of parameters, though nothing seems to impact this. I have saved out two input pointclouds that I try to align with the icp, you can download them here if you like. I'm pretty much out of ideas on this. Unfortunately the documentation is rather lacking...

To further clarify what I'm doing:

pcl::IterativeClosestPoint<pcl::PointXYZRGB,pcl::PointXYZRGB> icp;
icp.setInputCloud(inputcloud.makeShared());
icp.setInputTarget(targetcloud.makeShared());
pcl::PointCloud<pcl::PointXYZRGB> final;
icp.align(final);

The above download contains inputcloud and targetcloud as they are saved right before icp.align().

UPDATE2: Using the ICP test sample program and the provided sample files bun0.pcd and bun4.pcd I found out that the problem seems to be specific to my pointclouds as those samples work fine. Are there any preconditions that the pointclouds must fulfill for ICP to work?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
3

answered 2011-08-10 01:14:19 -0600

this post is marked as community wiki

This post is a wiki. Anyone with karma >75 is welcome to improve it.

Ok, since I can also answer my own question, I'll do just that. Apparently the pointclouds I got from the Kinect contained some NaN or Inf values, which the ICP doesn't like. It's kinda obvious that the nearest neighbour search with those values cannot really succeed, a better error message in that case would've saved some time :-)

Anyway, to fix that one can apply a simple passthrough filter to the Kinect pointcloud like this:

pcl::PassThrough<pcl::PointXYZRGB> pass; // can do this without parameters
pass.setInputCloud( input );
pass.filter( output );

You'll have to do this for both, input and target cloud. Then give the filtered clouds to the ICP.

Alternatively one can use pcl::removeNaNFromPointCloud.

If someone knows a more elegant way to get rid of the NaN or Inf points than that - feel free to edit this post :-)

edit flag offensive delete link more

Comments

i love you

Sentinal_Bias gravatar image Sentinal_Bias  ( 2013-06-06 03:38:35 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2011-08-08 21:39:07 -0600

Seen: 2,831 times

Last updated: Oct 28 '11