Public Types | Public Member Functions | Static Public Attributes | Private Attributes | List of all members
ApproxMVBB::KdTree::NearestNeighbourFilter< TTraits > Class Template Reference

#include <KdTree.hpp>

Public Types

using NearestDistancesType = std::vector< PREC >
 
using NodeDataType = typename Tree::NodeDataType
 
using PointDataTraits = TTraits
 
using PointGetter = typename PointDataTraits::PointGetter
 
using PointListType = typename PointDataTraits::PointListType
 
using PointType = typename PointDataTraits::PointType
 
using SplitHeuristicType = typename Tree::SplitHeuristicType
 
using Tree = KdTree::Tree< KdTree::TreeTraits< KdTree::PointData< PointDataTraits > > >
 

Public Member Functions

template<typename Container , typename DistSq = EuclideanDistSq, typename = typename std::enable_if<ContainerTags::has_randomAccessIterator<Container>::value>::type>
void filter (Container &points, const AABB< Dim > &aabb, Container &output, bool invert=false)
 
std::pair< PREC, PREC > getMoments ()
 
std::vector< PREC > & getNearestDists ()
 
std::tuple< std::size_t, PREC, std::size_t > getSettings ()
 
 NearestNeighbourFilter (std::size_t kNeighboursMean=20, PREC stdDevMult=1.0, std::size_t allowSplitAboveNPoints=10)
 
void setSettings (std::size_t kNeighboursMean, PREC stdDevMult, std::size_t allowSplitAboveNPoints)
 

Static Public Attributes

static const unsigned int Dim = PointDataTraits::Dimension
 

Private Attributes

std::size_t m_allowSplitAboveNPoints
 
std::size_t m_kNeighboursMean
 
PREC m_mean = 0
 
NearestDistancesType m_nearestDists
 
PREC m_stdDev = 0
 
PREC m_stdDevMult
 

Detailed Description

template<typename TTraits = KdTree::DefaultPointDataTraits<>>
class ApproxMVBB::KdTree::NearestNeighbourFilter< TTraits >

=======================================================================================

Definition at line 2419 of file KdTree.hpp.

Member Typedef Documentation

template<typename TTraits = KdTree::DefaultPointDataTraits<>>
using ApproxMVBB::KdTree::NearestNeighbourFilter< TTraits >::NearestDistancesType = std::vector<PREC>

Get the nearestDists for all points from the filter. Take care, these values at index i do really correspond to index in points in filter(). because filter() function may have changed the order which is also reflected in the return value of this function.

Definition at line 2586 of file KdTree.hpp.

template<typename TTraits = KdTree::DefaultPointDataTraits<>>
using ApproxMVBB::KdTree::NearestNeighbourFilter< TTraits >::NodeDataType = typename Tree::NodeDataType

Definition at line 2433 of file KdTree.hpp.

template<typename TTraits = KdTree::DefaultPointDataTraits<>>
using ApproxMVBB::KdTree::NearestNeighbourFilter< TTraits >::PointDataTraits = TTraits

Definition at line 2422 of file KdTree.hpp.

template<typename TTraits = KdTree::DefaultPointDataTraits<>>
using ApproxMVBB::KdTree::NearestNeighbourFilter< TTraits >::PointGetter = typename PointDataTraits::PointGetter

Definition at line 2426 of file KdTree.hpp.

template<typename TTraits = KdTree::DefaultPointDataTraits<>>
using ApproxMVBB::KdTree::NearestNeighbourFilter< TTraits >::PointListType = typename PointDataTraits::PointListType

Definition at line 2424 of file KdTree.hpp.

template<typename TTraits = KdTree::DefaultPointDataTraits<>>
using ApproxMVBB::KdTree::NearestNeighbourFilter< TTraits >::PointType = typename PointDataTraits::PointType

Definition at line 2425 of file KdTree.hpp.

template<typename TTraits = KdTree::DefaultPointDataTraits<>>
using ApproxMVBB::KdTree::NearestNeighbourFilter< TTraits >::SplitHeuristicType = typename Tree::SplitHeuristicType

Definition at line 2432 of file KdTree.hpp.

template<typename TTraits = KdTree::DefaultPointDataTraits<>>
using ApproxMVBB::KdTree::NearestNeighbourFilter< TTraits >::Tree = KdTree::Tree< KdTree::TreeTraits< KdTree::PointData<PointDataTraits> > >

Definition at line 2431 of file KdTree.hpp.

Constructor & Destructor Documentation

template<typename TTraits = KdTree::DefaultPointDataTraits<>>
ApproxMVBB::KdTree::NearestNeighbourFilter< TTraits >::NearestNeighbourFilter ( std::size_t  kNeighboursMean = 20,
PREC  stdDevMult = 1.0,
std::size_t  allowSplitAboveNPoints = 10 
)
inline

CTor

Definition at line 2436 of file KdTree.hpp.

Member Function Documentation

template<typename TTraits = KdTree::DefaultPointDataTraits<>>
template<typename Container , typename DistSq = EuclideanDistSq, typename = typename std::enable_if<ContainerTags::has_randomAccessIterator<Container>::value>::type>
void ApproxMVBB::KdTree::NearestNeighbourFilter< TTraits >::filter ( Container &  points,
const AABB< Dim > &  aabb,
Container &  output,
bool  invert = false 
)
inline

This filter function computes the nearest distance distribution (mean, standart deviation) of the points points and classifies all points which have mean nearest distance < mean + stdDevMult * standart deviation as outliers. The AABB aabb is for building the kd-Tree. The function modifies the container points (shuffling, sorting etc.) and saves the remaining points in output. If invert is on the outliers are saved in output.

Definition at line 2472 of file KdTree.hpp.

template<typename TTraits = KdTree::DefaultPointDataTraits<>>
std::pair<PREC,PREC> ApproxMVBB::KdTree::NearestNeighbourFilter< TTraits >::getMoments ( )
inline

Get the computed mean/standart deviation of the nearest distance (the mean of the returned array of getNearestDists())

Definition at line 2594 of file KdTree.hpp.

template<typename TTraits = KdTree::DefaultPointDataTraits<>>
std::vector<PREC>& ApproxMVBB::KdTree::NearestNeighbourFilter< TTraits >::getNearestDists ( )
inline

Definition at line 2587 of file KdTree.hpp.

template<typename TTraits = KdTree::DefaultPointDataTraits<>>
std::tuple<std::size_t,PREC,std::size_t> ApproxMVBB::KdTree::NearestNeighbourFilter< TTraits >::getSettings ( )
inline

Definition at line 2446 of file KdTree.hpp.

template<typename TTraits = KdTree::DefaultPointDataTraits<>>
void ApproxMVBB::KdTree::NearestNeighbourFilter< TTraits >::setSettings ( std::size_t  kNeighboursMean,
PREC  stdDevMult,
std::size_t  allowSplitAboveNPoints 
)
inline

Definition at line 2451 of file KdTree.hpp.

Member Data Documentation

template<typename TTraits = KdTree::DefaultPointDataTraits<>>
const unsigned int ApproxMVBB::KdTree::NearestNeighbourFilter< TTraits >::Dim = PointDataTraits::Dimension
static

Definition at line 2423 of file KdTree.hpp.

template<typename TTraits = KdTree::DefaultPointDataTraits<>>
std::size_t ApproxMVBB::KdTree::NearestNeighbourFilter< TTraits >::m_allowSplitAboveNPoints
private

Definition at line 2613 of file KdTree.hpp.

template<typename TTraits = KdTree::DefaultPointDataTraits<>>
std::size_t ApproxMVBB::KdTree::NearestNeighbourFilter< TTraits >::m_kNeighboursMean
private

How many neighbours points are search for one point to classify to build the mean neighbour distance

Definition at line 2606 of file KdTree.hpp.

template<typename TTraits = KdTree::DefaultPointDataTraits<>>
PREC ApproxMVBB::KdTree::NearestNeighbourFilter< TTraits >::m_mean = 0
private

Definition at line 2602 of file KdTree.hpp.

template<typename TTraits = KdTree::DefaultPointDataTraits<>>
NearestDistancesType ApproxMVBB::KdTree::NearestNeighbourFilter< TTraits >::m_nearestDists
private

Definition at line 2601 of file KdTree.hpp.

template<typename TTraits = KdTree::DefaultPointDataTraits<>>
PREC ApproxMVBB::KdTree::NearestNeighbourFilter< TTraits >::m_stdDev = 0
private

Definition at line 2603 of file KdTree.hpp.

template<typename TTraits = KdTree::DefaultPointDataTraits<>>
PREC ApproxMVBB::KdTree::NearestNeighbourFilter< TTraits >::m_stdDevMult
private

The multiplier for the standart deviation, if the distance of the point to classify is > stdDevMult * stdDevDist + meanDist, then the point is classfied as an outlier.

Definition at line 2611 of file KdTree.hpp.


The documentation for this class was generated from the following file:


asr_approx_mvbb
Author(s): Gassner Nikolai
autogenerated on Mon Jun 10 2019 12:38:09