Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | Friends
lslgeneric::OctTree< PointT > Class Template Reference

An Oct Tree data structure for storing 3D points. More...

#include <oc_tree.h>

Inheritance diagram for lslgeneric::OctTree< PointT >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual Cell< PointT > * addPoint (const PointT &point)
 add a point to the index
virtual SpatialIndex< PointT >
::CellVectorItr 
begin ()
 iterator through all cells in index, points at the begining
virtual SpatialIndex< PointT > * clone () const
 cloning method inherited from spatial index
virtual SpatialIndex< PointT > * copy () const
virtual SpatialIndex< PointT >
::CellVectorItr 
end ()
 iterator through all cells in index, points at the end
virtual Cell< PointT > * getCellForPoint (const PointT &point)
 returns a pointer to the cell containing the point or NULL if not found
OctTree< PointT > * getChild (int idx)
 returns a child at the specified index
virtual Cell< PointT > * getClosestLeafCell (const PointT &pt)
virtual NDTCell< PointT > * getClosestNDTCell (const PointT &pt)
virtual OctTree< PointT > * getLeafForPoint (const PointT &point)
virtual Cell< PointT > * getMyCell ()
virtual void getNeighbors (const PointT &point, const double &radius, std::vector< Cell< PointT > * > &cells)
virtual bool intersectSphere (const PointT center, const double &radius) const
bool isLeaf ()
 OctTree ()
 dummy default constructor
 OctTree (PointT center, double xsize, double ysize, double zsize, NDTCell< PointT > *type, OctTree< PointT > *_parent=NULL, unsigned int _depth=0)
 creates an oct tree node with known center and size
void print ()
 recursively print the tree
virtual void setCellType (Cell< PointT > *type)
 sets the prototype for a cell
virtual void setCenter (const double &cx, const double &cy, const double &cz)
void setParameters (double _BIG_CELL_SIZE=4, double _SMALL_CELL_SIZE=0.5, int _MAX_POINTS=10, int _MAX_DEPTH=20)
 use this to set the parameters for the OctTree - will *only* apply to leafs of the current node.
virtual void setSize (const double &sx, const double &sy, const double &sz)
void writeToVRML (const char *filename)
 output methods to a vrml file. draws the cell sizes and all points
void writeToVRML (FILE *fout)
virtual ~OctTree ()

Public Attributes

double BIG_CELL_SIZE
int MAX_DEPTH
int MAX_POINTS
bool parametersSet_
double SMALL_CELL_SIZE

Protected Member Functions

virtual void computeLeafCells ()
 fills in the leafs vector when needed
virtual size_t getIndexForPoint (const PointT &pt) const
 checks in which child node a point would belong

Protected Attributes

OctTreechildren_ [8]
unsigned int depth_
bool leaf_
bool leafsCached_
NDTCell< PointT > * myCell_
std::vector< Cell< PointT > * > myLeafs_
OctTreeparent_

Friends

class AdaptiveOctTree< PointT >

Detailed Description

template<typename PointT>
class lslgeneric::OctTree< PointT >

An Oct Tree data structure for storing 3D points.

This is an implementation of a SpatialIndex that splits space using a tree structure. Each node has 8 children that do not necessarily have associated points. Points are stored using NDTCell cells. When inserting points the tree is split until the size BIG_CELL is reached. Further splits occur when the number of points in a leaf goes above the MAX_POINTS threshold

Definition at line 57 of file oc_tree.h.


Constructor & Destructor Documentation

template<typename PointT >
lslgeneric::OctTree< PointT >::OctTree ( )

dummy default constructor

empty constructor

Definition at line 81 of file oc_tree.hpp.

template<typename PointT >
lslgeneric::OctTree< PointT >::OctTree ( PointT  center,
double  xsize,
double  ysize,
double  zsize,
NDTCell< PointT > *  type,
OctTree< PointT > *  _parent = NULL,
unsigned int  _depth = 0 
)

creates an oct tree node with known center and size

parametrized constructor

Definition at line 99 of file oc_tree.hpp.

template<typename PointT >
lslgeneric::OctTree< PointT >::~OctTree ( ) [virtual]

destructor, deletes all pointers starting from parent and going down

Definition at line 129 of file oc_tree.hpp.


Member Function Documentation

template<typename PointT >
Cell< PointT > * lslgeneric::OctTree< PointT >::addPoint ( const PointT &  point_c) [virtual]

add a point to the index

adds a point to the index. Iterates down the tree and if necessary creates new leafs and splits current ones.

Note:
at the moment root is not grown in case of points outside!

Implements lslgeneric::SpatialIndex< PointT >.

Definition at line 151 of file oc_tree.hpp.

template<typename PointT >
SpatialIndex< PointT >::CellVectorItr lslgeneric::OctTree< PointT >::begin ( ) [virtual]

iterator through all cells in index, points at the begining

iterator poining to the first leaf cell.

Note:
recomputes the vector when changes have occured!

Implements lslgeneric::SpatialIndex< PointT >.

Definition at line 325 of file oc_tree.hpp.

template<typename PointT >
SpatialIndex< PointT > * lslgeneric::OctTree< PointT >::clone ( ) const [virtual]

cloning method inherited from spatial index

returns a new OctTree spatial index

Implements lslgeneric::SpatialIndex< PointT >.

Definition at line 396 of file oc_tree.hpp.

template<typename PointT >
void lslgeneric::OctTree< PointT >::computeLeafCells ( ) [protected, virtual]

fills in the leafs vector when needed

finds all children cells that are located at current leafs

Definition at line 269 of file oc_tree.hpp.

template<typename PointT >
SpatialIndex< PointT > * lslgeneric::OctTree< PointT >::copy ( ) const [virtual]

copies the spatial index

Implements lslgeneric::SpatialIndex< PointT >.

Definition at line 410 of file oc_tree.hpp.

template<typename PointT >
SpatialIndex< PointT >::CellVectorItr lslgeneric::OctTree< PointT >::end ( ) [virtual]

iterator through all cells in index, points at the end

iterator poining at last leaf cell

Implements lslgeneric::SpatialIndex< PointT >.

Definition at line 339 of file oc_tree.hpp.

template<typename PointT >
Cell< PointT > * lslgeneric::OctTree< PointT >::getCellForPoint ( const PointT &  point) [virtual]

returns a pointer to the cell containing the point or NULL if not found

returns the cell that should hold the point

Implements lslgeneric::SpatialIndex< PointT >.

Definition at line 233 of file oc_tree.hpp.

template<typename PointT>
OctTree<PointT>* lslgeneric::OctTree< PointT >::getChild ( int  idx) [inline]

returns a child at the specified index

Definition at line 129 of file oc_tree.h.

template<typename PointT >
Cell< PointT > * lslgeneric::OctTree< PointT >::getClosestLeafCell ( const PointT &  pt) [virtual]

Definition at line 547 of file oc_tree.hpp.

template<typename PointT >
NDTCell< PointT > * lslgeneric::OctTree< PointT >::getClosestNDTCell ( const PointT &  pt) [virtual]

Definition at line 594 of file oc_tree.hpp.

template<typename PointT >
size_t lslgeneric::OctTree< PointT >::getIndexForPoint ( const PointT &  pt) const [protected, virtual]

checks in which child node a point would belong

returns the child index that should hold the point.

Note:
the point is not necessarily within the child's boundaries, but is guaranteed to be in the same quadrant (octant?)

index table: (convenient computations) id x y z 0 + + + 1 + + - 2 + - - 3 + - + 4 - + + 5 - + - 6 - - - 7 - - +

Definition at line 38 of file oc_tree.hpp.

template<typename PointT >
OctTree< PointT > * lslgeneric::OctTree< PointT >::getLeafForPoint ( const PointT &  point) [virtual]

finds the leaf that should hold the point

Definition at line 244 of file oc_tree.hpp.

template<typename PointT>
virtual Cell<PointT>* lslgeneric::OctTree< PointT >::getMyCell ( ) [inline, virtual]

Definition at line 107 of file oc_tree.h.

template<typename PointT >
void lslgeneric::OctTree< PointT >::getNeighbors ( const PointT &  point,
const double &  radius,
std::vector< Cell< PointT > * > &  cells 
) [virtual]

returns all the neighboring cells within a radius

Parameters:
pointthe location around which we are looking for neighbors. The point must be inside the boundaries of a current leaf!
radiusthe neighbor tolerance
cellsoutput

Implements lslgeneric::SpatialIndex< PointT >.

Definition at line 465 of file oc_tree.hpp.

template<typename PointT >
bool lslgeneric::OctTree< PointT >::intersectSphere ( const PointT  center,
const double &  radius 
) const [virtual]

checks if the tree node intersects the sphere located at center_ and of size radius

Definition at line 531 of file oc_tree.hpp.

template<typename PointT>
bool lslgeneric::OctTree< PointT >::isLeaf ( ) [inline]

Definition at line 137 of file oc_tree.h.

template<typename PointT>
void lslgeneric::OctTree< PointT >::print ( )

recursively print the tree

template<typename PointT >
void lslgeneric::OctTree< PointT >::setCellType ( Cell< PointT > *  type) [virtual]

sets the prototype for a cell

sets the cell factory type

Implements lslgeneric::SpatialIndex< PointT >.

Definition at line 309 of file oc_tree.hpp.

template<typename PointT >
void lslgeneric::OctTree< PointT >::setCenter ( const double &  cx,
const double &  cy,
const double &  cz 
) [virtual]

sets the center_.

Note:
this is not going to re-compute cells that are already in the tree!

Reimplemented from lslgeneric::SpatialIndex< PointT >.

Definition at line 432 of file oc_tree.hpp.

template<typename PointT >
void lslgeneric::OctTree< PointT >::setParameters ( double  _BIG_CELL_SIZE = 4,
double  _SMALL_CELL_SIZE = 0.5,
int  _MAX_POINTS = 10,
int  _MAX_DEPTH = 20 
)

use this to set the parameters for the OctTree - will *only* apply to leafs of the current node.

Definition at line 7 of file oc_tree.hpp.

template<typename PointT >
void lslgeneric::OctTree< PointT >::setSize ( const double &  sx,
const double &  sy,
const double &  sz 
) [virtual]

sets the size

Note:
this is not going to re-compute cells that are already in the tree!

Reimplemented from lslgeneric::SpatialIndex< PointT >.

Definition at line 450 of file oc_tree.hpp.

template<typename PointT >
void lslgeneric::OctTree< PointT >::writeToVRML ( const char *  filename)

output methods to a vrml file. draws the cell sizes and all points

output to vrml

Definition at line 353 of file oc_tree.hpp.

template<typename PointT >
void lslgeneric::OctTree< PointT >::writeToVRML ( FILE *  fout)

output to vrml using file pointer

Definition at line 375 of file oc_tree.hpp.


Friends And Related Function Documentation

template<typename PointT>
friend class AdaptiveOctTree< PointT > [friend]

Definition at line 155 of file oc_tree.h.


Member Data Documentation

template<typename PointT>
double lslgeneric::OctTree< PointT >::BIG_CELL_SIZE
Parameters:
splittree up to this size before allocating a cell

Definition at line 85 of file oc_tree.h.

template<typename PointT>
OctTree* lslgeneric::OctTree< PointT >::children_[8] [protected]

Definition at line 61 of file oc_tree.h.

template<typename PointT>
unsigned int lslgeneric::OctTree< PointT >::depth_ [protected]

Definition at line 65 of file oc_tree.h.

template<typename PointT>
bool lslgeneric::OctTree< PointT >::leaf_ [protected]

Definition at line 66 of file oc_tree.h.

template<typename PointT>
bool lslgeneric::OctTree< PointT >::leafsCached_ [protected]

Definition at line 67 of file oc_tree.h.

template<typename PointT>
int lslgeneric::OctTree< PointT >::MAX_DEPTH
Parameters:
maximumdepth of the tree, after which no more splits

Definition at line 79 of file oc_tree.h.

template<typename PointT>
int lslgeneric::OctTree< PointT >::MAX_POINTS
Parameters:
numberof points after which to split cell

Definition at line 81 of file oc_tree.h.

template<typename PointT>
NDTCell<PointT>* lslgeneric::OctTree< PointT >::myCell_ [protected]

Definition at line 62 of file oc_tree.h.

template<typename PointT>
std::vector< Cell<PointT>* > lslgeneric::OctTree< PointT >::myLeafs_ [protected]

Definition at line 64 of file oc_tree.h.

template<typename PointT>
bool lslgeneric::OctTree< PointT >::parametersSet_

Definition at line 86 of file oc_tree.h.

template<typename PointT>
OctTree* lslgeneric::OctTree< PointT >::parent_ [protected]

Definition at line 60 of file oc_tree.h.

template<typename PointT>
double lslgeneric::OctTree< PointT >::SMALL_CELL_SIZE
Parameters:
atthis level do not split any more

Definition at line 83 of file oc_tree.h.


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


ndt_map
Author(s): Todor Stoyanov, Jari Saarinen, Henrik Andreasson
autogenerated on Mon Jan 6 2014 11:31:57