Public Types | Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes | Friends | List of all members
lvr2::KDTree Class Referenceabstract

a kd-Tree Implementation for nearest Neighbor searches More...

#include <KDTree.hpp>

Inheritance diagram for lvr2::KDTree:
Inheritance graph
[legend]

Public Types

using KDTreePtr = std::shared_ptr< KDTree >
 
using Neighbor = Point *
 
using Point = Vector3< PointT >
 
using PointT = float
 

Public Member Functions

template<typename T >
bool nearestNeighbor (const Vector3< T > &point, Neighbor &neighbor, double &distance, double maxDistance=std::numeric_limits< double >::infinity()) const
 Finds the nearest neighbor of 'point' that is within 'maxDistance' (defaults to infinity). The resulting neighbor is written into 'neighbor' (or nullptr if none is found). More...
 
virtual ~KDTree ()=default
 

Static Public Member Functions

static std::shared_ptr< KDTreecreate (SLAMScanPtr scan, int maxLeafSize=20)
 Creates a new KDTree from the given Scan. More...
 
static size_t nearestNeighbors (KDTreePtr tree, SLAMScanPtr scan, KDTree::Neighbor *neighbors, double maxDistance)
 Finds the nearest neighbors of all points in a Scan using a pre-generated KDTree. More...
 
static size_t nearestNeighbors (KDTreePtr tree, SLAMScanPtr scan, Neighbor *neighbors, double maxDistance, Vector3d &centroid_m, Vector3d &centroid_d)
 Finds the nearest neighbors of all points in a Scan using a pre-generated KDTree. More...
 

Protected Member Functions

 KDTree ()=default
 
 KDTree (const KDTree &&)=delete
 
virtual void nnInternal (const Point &point, Neighbor &neighbor, double &maxDist) const =0
 

Protected Attributes

boost::shared_array< Pointpoints
 

Friends

class KDNode
 

Detailed Description

a kd-Tree Implementation for nearest Neighbor searches

Definition at line 51 of file KDTree.hpp.

Member Typedef Documentation

◆ KDTreePtr

using lvr2::KDTree::KDTreePtr = std::shared_ptr<KDTree>

Definition at line 57 of file KDTree.hpp.

◆ Neighbor

Definition at line 56 of file KDTree.hpp.

◆ Point

Definition at line 55 of file KDTree.hpp.

◆ PointT

using lvr2::KDTree::PointT = float

Definition at line 54 of file KDTree.hpp.

Constructor & Destructor Documentation

◆ ~KDTree()

virtual lvr2::KDTree::~KDTree ( )
virtualdefault

◆ KDTree() [1/2]

lvr2::KDTree::KDTree ( )
protecteddefault

◆ KDTree() [2/2]

lvr2::KDTree::KDTree ( const KDTree &&  )
protecteddelete

Member Function Documentation

◆ create()

KDTreePtr lvr2::KDTree::create ( SLAMScanPtr  scan,
int  maxLeafSize = 20 
)
static

Creates a new KDTree from the given Scan.

Parameters
pointsThe Point Cloud
nThe number of points in 'points'
maxLeafSizeThe maximum number of points to use for a Leaf in the Tree

Definition at line 153 of file KDTree.cpp.

◆ nearestNeighbor()

template<typename T >
bool lvr2::KDTree::nearestNeighbor ( const Vector3< T > &  point,
Neighbor neighbor,
double &  distance,
double  maxDistance = std::numeric_limits<double>::infinity() 
) const
inline

Finds the nearest neighbor of 'point' that is within 'maxDistance' (defaults to infinity). The resulting neighbor is written into 'neighbor' (or nullptr if none is found).

Parameters
pointThe Point whose neighbor is searched
neighborA Pointer that is set to the neighbor or nullptr if none is found
distanceThe final distance between point and neighbor
maxDistanceThe maximum distance allowed between neighbors. Setting this value significantly speeds up the search.
Returns
bool true if a neighbors was found, false otherwise

Definition at line 80 of file KDTree.hpp.

◆ nearestNeighbors() [1/2]

size_t lvr2::KDTree::nearestNeighbors ( KDTreePtr  tree,
SLAMScanPtr  scan,
KDTree::Neighbor neighbors,
double  maxDistance 
)
static

Finds the nearest neighbors of all points in a Scan using a pre-generated KDTree.

Parameters
treeThe KDTree to search in
scanThe Scan to search for
neighborsAn array to store the results in. neighbors[i] is set to a Pointer to the neighbor of points[i] or nullptr if none was found
maxDistanceThe maximum Distance for a Neighbor
Returns
size_t The number of neighbors that were found

Definition at line 198 of file KDTree.cpp.

◆ nearestNeighbors() [2/2]

size_t lvr2::KDTree::nearestNeighbors ( KDTreePtr  tree,
SLAMScanPtr  scan,
KDTree::Neighbor neighbors,
double  maxDistance,
Vector3d centroid_m,
Vector3d centroid_d 
)
static

Finds the nearest neighbors of all points in a Scan using a pre-generated KDTree.

Parameters
treeThe KDTree to search in
scanThe Scan to search for
neighborsAn array to store the results in. neighbors[i] is set to a Pointer to the neighbor of points[i] or nullptr if none was found
maxDistanceThe maximum Distance for a Neighbor
centroid_mWill be set to the average of all Points in 'neighbors'
centroid_dWill be set to the average of all Points in 'points' that have neighbors
Returns
size_t The number of neighbors that were found

Definition at line 176 of file KDTree.cpp.

◆ nnInternal()

virtual void lvr2::KDTree::nnInternal ( const Point point,
Neighbor neighbor,
double &  maxDist 
) const
protectedpure virtual

Implemented in lvr2::KDLeaf, and lvr2::KDNode.

Friends And Related Function Documentation

◆ KDNode

friend class KDNode
friend

Definition at line 130 of file KDTree.hpp.

Member Data Documentation

◆ points

boost::shared_array<Point> lvr2::KDTree::points
protected

Definition at line 132 of file KDTree.hpp.


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


lvr2
Author(s): Thomas Wiemann , Sebastian Pütz , Alexander Mock , Lars Kiesow , Lukas Kalbertodt , Tristan Igelbrink , Johan M. von Behren , Dominik Feldschnieders , Alexander Löhr
autogenerated on Wed Mar 2 2022 00:37:27