Public Member Functions | Private Member Functions | Private Attributes | List of all members
lvr2::AdaptiveKSearchSurface< BaseVecT > Class Template Reference

A point cloud manager class that uses the STANN nearest neighbor search library to handle the data. This class calculates robust surface normals for the given point set as described in the SSRR2010 paper. More...

#include <AdaptiveKSearchSurface.hpp>

Inheritance diagram for lvr2::AdaptiveKSearchSurface< BaseVecT >:
Inheritance graph
[legend]

Public Member Functions

 AdaptiveKSearchSurface ()
 standard Constructor More...
 
 AdaptiveKSearchSurface (PointBufferPtr loader, std::string searchTreeName, int kn=10, int ki=10, int kd=10, int calcMethod=0, string poseFile="")
 Constructor. More...
 
virtual void calculateSurfaceNormals ()
 Calculates initial point normals using a least squares fit to the m_kn nearest points. More...
 
virtual pair< typename BaseVecT::CoordType, typename BaseVecT::CoordType > distance (BaseVecT v) const
 See interface documentation. More...
 
void interpolateSurfaceNormals ()
 Interpolate the initial normals with the m_ki neighbors. More...
 
virtual ~AdaptiveKSearchSurface ()
 Destructor. More...
 
- Public Member Functions inherited from lvr2::PointsetSurface< BaseVecT >
const BoundingBox< BaseVecT > & getBoundingBox () const
 Returns the bounding box of the point set. More...
 
virtual Normal< float > getInterpolatedNormal (const BaseVecT &position) const
 Interpolates a surface normal at the given position. More...
 
virtual PointBufferPtr pointBuffer () const
 Returns the internal point buffer. After a call of calculateSurfaceNormals the buffer will contain normal information. More...
 
std::shared_ptr< SearchTree< BaseVecT > > searchTree () const
 Returns a pointer to the search tree. More...
 
void setKd (int k)
 Sets the number of points that is used for distance evaluation, i.e. an average of the distance to the k nearest data points is given (useful in noisy data sets). More...
 
void setKi (int k)
 If k is > 0, each normal will be averaged with its k neighbors. More...
 
void setKn (int k)
 Sets the size of the k-neighborhood that is used for normal estimation. More...
 

Private Member Functions

bool boundingBoxOK (float dx, float dy, float dz)
 Checks if the bounding box of a point set is "well formed", i.e. no dimension is significantly larger than the other. More...
 
Plane< BaseVecT > calcPlane (const BaseVecT &queryPoint, int k, const vector< size_t > &id)
 Calculates a tangent plane for the query point using the provided k-neighborhood. More...
 
Plane< BaseVecT > calcPlaneIterative (const BaseVecT &queryPoint, int k, const vector< size_t > &id)
 
Plane< BaseVecT > calcPlaneRANSAC (const BaseVecT &queryPoint, int k, const vector< size_t > &id, bool &ok)
 
void init ()
 Helper function for constructors. More...
 
void parseScanPoses (string posefile)
 Parses the file with scan poses and creates a search tree to search for the nearest pose when flipping normals. More...
 

Private Attributes

int m_calcMethod
 
BaseVecT m_centroid
 The centroid of the point set. More...
 
std::shared_ptr< SearchTree< BaseVecT > > m_poseTree
 Search tree for scan poses. More...
 
string m_searchTreeName
 Type of used search tree. More...
 

Additional Inherited Members

- Protected Member Functions inherited from lvr2::PointsetSurface< BaseVecT >
 PointsetSurface ()
 
 PointsetSurface (PointBufferPtr pointcloud)
 Constructor. Stores the given buffer pointer. If the point buffer does not contain surface normals, you will have to call calculateSurfaceNormals before the first call @distance. More...
 
- Protected Attributes inherited from lvr2::PointsetSurface< BaseVecT >
BoundingBox< BaseVecT > m_boundingBox
 The bounding box of the point cloud. More...
 
int m_kd
 The number of points used for distance function evaluation. More...
 
int m_ki
 The number of points used for normal interpolation. More...
 
int m_kn
 The number of points used for normal estimation. More...
 
PointBufferPtr m_pointBuffer
 The point cloud used for surface approximation. More...
 
std::shared_ptr< SearchTree< BaseVecT > > m_searchTree
 The search tree that is built from the point cloud data. More...
 

Detailed Description

template<typename BaseVecT>
class lvr2::AdaptiveKSearchSurface< BaseVecT >

A point cloud manager class that uses the STANN nearest neighbor search library to handle the data. This class calculates robust surface normals for the given point set as described in the SSRR2010 paper.

Definition at line 98 of file AdaptiveKSearchSurface.hpp.

Constructor & Destructor Documentation

◆ AdaptiveKSearchSurface() [1/2]

template<typename BaseVecT >
lvr2::AdaptiveKSearchSurface< BaseVecT >::AdaptiveKSearchSurface ( PointBufferPtr  loader,
std::string  searchTreeName,
int  kn = 10,
int  ki = 10,
int  kd = 10,
int  calcMethod = 0,
string  poseFile = "" 
)

Constructor.

Parameters
Thefile to read from
searchTNThe of the searchTree type that shall be used
knThe number of neighbor points used for normal estimation
kiThe number of neighbor points used for normal interpolation
kdThe number of neighbor points used for distance value calculation
calcMethodNormal calculation method. 0: PCA(default), 1: RANSAC, 2: Iterative

◆ AdaptiveKSearchSurface() [2/2]

template<typename BaseVecT >
lvr2::AdaptiveKSearchSurface< BaseVecT >::AdaptiveKSearchSurface ( )

standard Constructor

 m_useRANSAC = true;
 m_ki = 10;
 m_kn = 10;
 m_kd = 10;

 This Constructor can be used, if only the method "calcPlaneRANSACfromPoints"
 is required

◆ ~AdaptiveKSearchSurface()

template<typename BaseVecT >
virtual lvr2::AdaptiveKSearchSurface< BaseVecT >::~AdaptiveKSearchSurface ( )
inlinevirtual

Destructor.

Definition at line 140 of file AdaptiveKSearchSurface.hpp.

Member Function Documentation

◆ boundingBoxOK()

template<typename BaseVecT >
bool lvr2::AdaptiveKSearchSurface< BaseVecT >::boundingBoxOK ( float  dx,
float  dy,
float  dz 
)
private

Checks if the bounding box of a point set is "well formed", i.e. no dimension is significantly larger than the other.

This method is needed to achieve a better quality of the initial normal estimation in sparse scans. Details are described in the SRR2010 paper.

Parameters
dx,dy,dzThe side lengths of the bounding box
Returns
true if the given box has valid dimensions.

◆ calcPlane()

template<typename BaseVecT >
Plane<BaseVecT> lvr2::AdaptiveKSearchSurface< BaseVecT >::calcPlane ( const BaseVecT &  queryPoint,
int  k,
const vector< size_t > &  id 
)
private

Calculates a tangent plane for the query point using the provided k-neighborhood.

Parameters
queryPointThe point for which the tangent plane is created
kThe size of the used k-neighborhood
idThe positions of the neighborhood points in m_points
okTrue, if RANSAC interpolation was succesfull

◆ calcPlaneIterative()

template<typename BaseVecT >
Plane<BaseVecT> lvr2::AdaptiveKSearchSurface< BaseVecT >::calcPlaneIterative ( const BaseVecT &  queryPoint,
int  k,
const vector< size_t > &  id 
)
private

◆ calcPlaneRANSAC()

template<typename BaseVecT >
Plane<BaseVecT> lvr2::AdaptiveKSearchSurface< BaseVecT >::calcPlaneRANSAC ( const BaseVecT &  queryPoint,
int  k,
const vector< size_t > &  id,
bool &  ok 
)
private

◆ calculateSurfaceNormals()

template<typename BaseVecT >
virtual void lvr2::AdaptiveKSearchSurface< BaseVecT >::calculateSurfaceNormals ( )
virtual

Calculates initial point normals using a least squares fit to the m_kn nearest points.

Implements lvr2::PointsetSurface< BaseVecT >.

◆ distance()

template<typename BaseVecT >
virtual pair<typename BaseVecT::CoordType, typename BaseVecT::CoordType> lvr2::AdaptiveKSearchSurface< BaseVecT >::distance ( BaseVecT  v) const
virtual

See interface documentation.

Implements lvr2::PointsetSurface< BaseVecT >.

◆ init()

template<typename BaseVecT >
void lvr2::AdaptiveKSearchSurface< BaseVecT >::init ( )
private

Helper function for constructors.

◆ interpolateSurfaceNormals()

template<typename BaseVecT >
void lvr2::AdaptiveKSearchSurface< BaseVecT >::interpolateSurfaceNormals ( )

Interpolate the initial normals with the m_ki neighbors.

◆ parseScanPoses()

template<typename BaseVecT >
void lvr2::AdaptiveKSearchSurface< BaseVecT >::parseScanPoses ( string  posefile)
private

Parses the file with scan poses and creates a search tree to search for the nearest pose when flipping normals.

Member Data Documentation

◆ m_calcMethod

template<typename BaseVecT >
int lvr2::AdaptiveKSearchSurface< BaseVecT >::m_calcMethod
private

Definition at line 308 of file AdaptiveKSearchSurface.hpp.

◆ m_centroid

template<typename BaseVecT >
BaseVecT lvr2::AdaptiveKSearchSurface< BaseVecT >::m_centroid
private

The centroid of the point set.

Definition at line 303 of file AdaptiveKSearchSurface.hpp.

◆ m_poseTree

template<typename BaseVecT >
std::shared_ptr<SearchTree<BaseVecT> > lvr2::AdaptiveKSearchSurface< BaseVecT >::m_poseTree
private

Search tree for scan poses.

Definition at line 322 of file AdaptiveKSearchSurface.hpp.

◆ m_searchTreeName

template<typename BaseVecT >
string lvr2::AdaptiveKSearchSurface< BaseVecT >::m_searchTreeName
private

Type of used search tree.

Definition at line 325 of file AdaptiveKSearchSurface.hpp.


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


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