Updated FLANN library, faster radius search

classic Classic list List threaded Threaded
2 messages Options
Reply | Threaded
Open this post in threaded view
|

Updated FLANN library, faster radius search

Marius Muja-2
Hi all,

I have updated the FLANN library in ROS. The new version has faster
radius search, in all my tests it's faster than ANN's radius search. I
have also made a small change to the pcl::KdTree::radiusSearch
method(s), by changing the return type from bool to int and changing
slightly the method's behavior as follows:

 1. if the k_indices and k_distances vectors have a size different
then the size of the point cloud when the function is called, the
function resizes them to the number of neighbors found. This is the
same behavior as until now with the exception that the function
returns the number of neighbors found instead of true/false. This
behavior has the disadvantage that it could trigger many memory
allocations when resizing the vectors and also requires the kd-tree to
be traversed twice, first to find the number of neighbors for resizing
the vectors and then to find the neighbors.

 2. when the two vectors are preallocated before the function is
called to have the same size as the point cloud, the function will not
resize the two vectors but only fill the first positions with the
neighbors found and return their number. This will be faster because
it requires no memory reallocations and the tree is only traversed
once. It requires a small change in the client code:

Old way:

kdtree.radiusSearch(point, radius, indices, dists);
for (size_t i=0;i<indices.size();++i) {
 // do something with indices[i] and dists[i]
}

New way:

// preallocate the vectors
indices.resize(cloud.points.size());
dists.resize(cloud.points.size());
int neighbors = kdtree.radiusSearch(point, radius, indices, dists);
for (int i=0;i<neighbors;++i) {
 // do something with indices[i] and dists[i]
}


The KdTreeFLANN index has also an additional feature: when the index
is constructed with the false argument ( kdtree = KdTreeFLANN(false)
), the radius search will not sort the neighbors which will be faster
that the default behavior (no argument to the constructor) when the
radiusSearch function returns the neighbors sorted by the distance to
the query point.


Marius
_______________________________________________
[hidden email] / http://pointclouds.org
https://code.ros.org/mailman/listinfo/pcl-users
Reply | Threaded
Open this post in threaded view
|

Re: Updated FLANN library, faster radius search

Radu B. Rusu
Administrator
And here's the test to prove it:

[==========] Running 5 tests from 1 test case.
[----------] Global test environment set-up.
[----------] 5 tests from PCL
[ RUN      ] PCL.KdTreeANN_radiusSearch
ANN radiusSearch took 20327.3ms.
[       OK ] PCL.KdTreeANN_radiusSearch
[ RUN      ] PCL.KdTreeFLANN_radiusSearch
FLANN radiusSearch took 9455.28ms.
FLANN radiusSearch (unsorted results) took 6640.11ms.
[       OK ] PCL.KdTreeFLANN_radiusSearch
[ RUN      ] PCL.KdTreeANN_nearestKSearch
ANN nearestKSearch took 4703.27ms.
[       OK ] PCL.KdTreeANN_nearestKSearch
[ RUN      ] PCL.KdTreeFLANN_nearestKSearch
FLANN nearestKSearch took 3048.59ms.
[       OK ] PCL.KdTreeFLANN_nearestKSearch
[ RUN      ] PCL.KdTreeANN_setPointRepresentation
[       OK ] PCL.KdTreeANN_setPointRepresentation
[----------] Global test environment tear-down
[==========] 5 tests from 1 test case ran.
[  PASSED  ] 5 tests.


_Awesome_ job Marius!!! 3 times faster than ANN for radiusSearch!

Ok, let's clean up the ANN mess, remove it from trunk, and prepare for a 0.7 release. Does anyone want any new features
or patches applied before 0.7?

Cheers,
Radu.
--
http://pointclouds.org

On 12/11/2010 09:25 AM, Marius Muja wrote:

> Hi all,
>
> I have updated the FLANN library in ROS. The new version has faster
> radius search, in all my tests it's faster than ANN's radius search. I
> have also made a small change to the pcl::KdTree::radiusSearch
> method(s), by changing the return type from bool to int and changing
> slightly the method's behavior as follows:
>
>   1. if the k_indices and k_distances vectors have a size different
> then the size of the point cloud when the function is called, the
> function resizes them to the number of neighbors found. This is the
> same behavior as until now with the exception that the function
> returns the number of neighbors found instead of true/false. This
> behavior has the disadvantage that it could trigger many memory
> allocations when resizing the vectors and also requires the kd-tree to
> be traversed twice, first to find the number of neighbors for resizing
> the vectors and then to find the neighbors.
>
>   2. when the two vectors are preallocated before the function is
> called to have the same size as the point cloud, the function will not
> resize the two vectors but only fill the first positions with the
> neighbors found and return their number. This will be faster because
> it requires no memory reallocations and the tree is only traversed
> once. It requires a small change in the client code:
>
> Old way:
>
> kdtree.radiusSearch(point, radius, indices, dists);
> for (size_t i=0;i<indices.size();++i) {
>   // do something with indices[i] and dists[i]
> }
>
> New way:
>
> // preallocate the vectors
> indices.resize(cloud.points.size());
> dists.resize(cloud.points.size());
> int neighbors = kdtree.radiusSearch(point, radius, indices, dists);
> for (int i=0;i<neighbors;++i) {
>   // do something with indices[i] and dists[i]
> }
>
>
> The KdTreeFLANN index has also an additional feature: when the index
> is constructed with the false argument ( kdtree = KdTreeFLANN(false)
> ), the radius search will not sort the neighbors which will be faster
> that the default behavior (no argument to the constructor) when the
> radiusSearch function returns the neighbors sorted by the distance to
> the query point.
>
>
> Marius
> _______________________________________________
> [hidden email] / http://pointclouds.org
> https://code.ros.org/mailman/listinfo/pcl-users
_______________________________________________
[hidden email] / http://pointclouds.org
https://code.ros.org/mailman/listinfo/pcl-users