Hi Björn, it could very well be that it is slow, as I just noticed that the cluster tolerance (i.e. maximum acceptable nearest neighbors distance) is set to 5 cm. On the Kinect points are much denser, so you can decrease that a lot, maybe 0.005 or less. That will speed up the nearest neighbor searches. There are lost of other optimizations possible, but they are not so straightforward. In the worst case, you can also try downsampling the PCD using a voxel grid: http://www.pointclouds.org/documentation/tutorials/voxel_grid.php Could you maybe subscribe to the pcl-users mailing list? This conversation seems to fit better there. Cheers, Zoltan On Mon, 2011-04-18 at 18:53 +0200, Björn Giesler wrote: > Hi, > > thanks for the code! I've tried it, and it runs... but either it gets stuck in an infinite loop or it takes a very long time (>10min.) for one image. Can that be right? I've tried debugging into it, but this is over my head... > > Regards, > Björn > > Am 18.04.2011 um 17:59 schrieb Zoltan-Csaba Marton: > > > Hi Björn, > > > > PCL has euclidean cluster extraction function and class and also convex > > hull.. but there is no tutorial for it yet. Nonetheless, it is very > > simple to use. Here is a hacked together sample code (suppose msg is > > your sensor_msgs::PointCloud2 input): > > > > pcl::PointCloud::Ptr cloud > > (new pcl::PointCloud); > > pcl::fromROSMsg (msg, *cloud); > > pcl::EuclideanClusterExtraction ece; > > std::vector clusters; > > ece.setInputCloud (cloud); > > ece.setMinClusterSize (10); > > ece.setClusterTolerance (0.05); > > ece.extract (clusters); > > ROS_INFO_STREAM ("No of clusters: " << clusters.size () << std::endl); > > > > Hope this helps. > > > > Cheers, > > Zoltan > > > > On Mon, 2011-04-18 at 17:35 +0200, Björn Giesler wrote: > >> Hi all, > >> > >> I'd like to use my robot's Kinect to find objects (obstacles / humans) in 3D. The way the sensor is integrated, it cannot see the ground plane, so segmentation should be very easy because no objects are connected by any structure. What I'm looking for is the simplest way to segment the point cloud into non-connected sub clouds or convex hulls thereof. I've found the border extraction tutorial, which kind of seems to do what I want... Is that it or is there an even simpler way? > >> > >> Thanks a lot & regards, > >> Björn > >> > >> Von meinem iPad gesendet > >> _______________________________________________ > >> ros-users mailing list > >> ros-users@code.ros.org > >> https://code.ros.org/mailman/listinfo/ros-users > > > > > > _______________________________________________ > > ros-users mailing list > > ros-users@code.ros.org > > https://code.ros.org/mailman/listinfo/ros-users >