4
$\begingroup$

I am investigating how a particular statistical outlier removal algorithm of 3D data works, but I am not able to properly figure out what they are doing.

The purpose of this algorithm, is to removal outlier points (in 3D space), and this algorithm is parameterized by k, which is the number of neighbors each points considers, and an std_threshold which seems to be a threshold on some standard deviation.

This explanation seems to be especially obtuse, where they claim it works by:

Our sparse outlier removal is based on the computation of the distribution of point to neighbors distances in the input dataset. For each point, we compute the mean distance from it to all its neighbors. By assuming that the resulted distribution is Gaussian with a mean and a standard deviation, all points whose mean distances are outside an interval defined by the global distances mean and standard deviation can be considered as outliers and trimmed from the dataset.

This explanation on the other hand claims that this algorithm works by:

Filtering points based on their local point densities, by removing points that are sparse relative to the mean point density of the whole cloud.

I am trying to attain a somewhat formalized explanation of this technique. I understand the intuition behind it, but I cannot seem to reconcile exactly what they are doing. Any help is appreciated. Thanks!

$\endgroup$

1 Answer 1

7
$\begingroup$

Surprisingly the algorithm isn't very complicated and the explanation on the pcl website is actually almost all there is to it. There's however some subtleties that don't appear in the above link, so here is a break down for more details.

  • Set k, an integer, representing the number of closest points around point $P_i$ (parameter setMeanK in pcl::StatisticalOutlierRemoval).
  • Set a standard deviation multiplier $\alpha$ (parameter setStddevMulThresh)
  • For every point $P_i$ in the 3D point cloud.
    • Find the location of the $k$ nearest neighbors to point $P_i$ (their indexes in the cloud)
    • Compute the average distance $d_i$ from point $P_i$ to its $k$ nearest neighbors.
  • Compute the mean $\mu_d$ of the distances $d_i$
  • Compute the standard deviation $\sigma_d$ of the distances $d_i$
  • Compute the threshold $T = \mu_d + \alpha \cdot \sigma_d$
  • Eliminate points in the cloud for which the average distance to its $k$ neighbours is at a distance $d > T$

The implementation therefore requires two passes over the whole set of points in the cloud:

  1. First pass to compute the mean and standard deviation of the distances from each points in the cloud to their $k$ nearest neighbours
  2. Second pass to eliminate all the points in the cloud which mean distance (computed in the first pass) is higher than the threshold defined above.

$Notes$:

1) While the algorithm will in effect eliminate points which distance to its $k$ nearest neighbors follows any statistical distribution, its parameters $\mu$ and $ \sigma$ are only meaningful for a normal (Gaussian) distribution.

2) the algorithm assumes the capability to obtain the k nearest neighbors of any given point in the point cloud.

$\endgroup$
1
  • $\begingroup$ So..., If I take a lower stddev_multiplier, I will reduce the (single, globally valid) T, thus making point removal more aggressive. Also, mean_k should not be selected larger than the smallest expected clusters? $\endgroup$ Commented Dec 4, 2023 at 16:30

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.

Not the answer you're looking for? Browse other questions tagged or ask your own question.