Public Member Functions | Private Attributes
lslgeneric::CellVector Class Reference

A spatial index represented as a grid map. More...

#include <cell_vector.h>

Inheritance diagram for lslgeneric::CellVector:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void addCell (NDTCell *cell)
void addCellPoints (pcl::PointCloud< pcl::PointXYZ > pc, const std::vector< size_t > &indices)
void addNDTCell (NDTCell *cell)
virtual NDTCelladdPoint (const pcl::PointXYZ &point)
 add a point and get back the pointer to the cell in which it ended up
virtual SpatialIndex::CellVectorItr begin ()
 iterator through all cells in index, points at the begining
 CellVector ()
 CellVector (NDTCell *cellPrototype)
 CellVector (const CellVector &other)
void cleanCellsAboveSize (double size)
virtual SpatialIndexclone () const
 clone - create an empty object with same type
virtual SpatialIndexcopy () const
 copy - create the same object as a new instance
virtual SpatialIndex::CellVectorItr end ()
 iterator through all cells in index, points at the end
virtual NDTCellgetCellForPoint (const pcl::PointXYZ &point)
NDTCellgetCellIdx (unsigned int idx) const
NDTCellgetClosestNDTCell (const pcl::PointXYZ &pt)
std::vector< NDTCell * > getClosestNDTCells (const pcl::PointXYZ &point, double &radius)
virtual void getNeighbors (const pcl::PointXYZ &point, const double &radius, std::vector< NDTCell * > &cells)
 method to return all cells within a certain radius from a point
void initKDTree ()
int loadFromJFF (FILE *jffin)
virtual void setCellType (NDTCell *type)
 sets the cell factory type
virtual int size ()
virtual ~CellVector ()

Private Attributes

std::vector< NDTCell * > activeCells
pcl::KdTreeFLANN< pcl::PointXYZ > meansTree
pcl::KdTree< pcl::PointXYZ >
::PointCloudPtr 
mp
NDTCellprotoType
bool treeUpdated

Detailed Description

A spatial index represented as a grid map.

A grid map with delayed allocation of cells.

Definition at line 49 of file cell_vector.h.


Constructor & Destructor Documentation

Definition at line 8 of file cell_vector.cpp.

Definition at line 15 of file cell_vector.cpp.

Definition at line 21 of file cell_vector.cpp.

Definition at line 34 of file cell_vector.cpp.


Member Function Documentation

Definition at line 94 of file cell_vector.cpp.

void lslgeneric::CellVector::addCellPoints ( pcl::PointCloud< pcl::PointXYZ >  pc,
const std::vector< size_t > &  indices 
)

Definition at line 85 of file cell_vector.cpp.

Definition at line 99 of file cell_vector.cpp.

NDTCell * lslgeneric::CellVector::addPoint ( const pcl::PointXYZ &  point) [virtual]

add a point and get back the pointer to the cell in which it ended up

Implements lslgeneric::SpatialIndex.

Definition at line 79 of file cell_vector.cpp.

iterator through all cells in index, points at the begining

Implements lslgeneric::SpatialIndex.

Definition at line 104 of file cell_vector.cpp.

Definition at line 234 of file cell_vector.cpp.

clone - create an empty object with same type

Implements lslgeneric::SpatialIndex.

Definition at line 120 of file cell_vector.cpp.

copy - create the same object as a new instance

Implements lslgeneric::SpatialIndex.

Definition at line 125 of file cell_vector.cpp.

iterator through all cells in index, points at the end

Implements lslgeneric::SpatialIndex.

Definition at line 110 of file cell_vector.cpp.

NDTCell * lslgeneric::CellVector::getCellForPoint ( const pcl::PointXYZ &  point) [virtual]

Implements lslgeneric::SpatialIndex.

Definition at line 46 of file cell_vector.cpp.

NDTCell * lslgeneric::CellVector::getCellIdx ( unsigned int  idx) const

Definition at line 227 of file cell_vector.cpp.

NDTCell * lslgeneric::CellVector::getClosestNDTCell ( const pcl::PointXYZ &  pt)

Definition at line 215 of file cell_vector.cpp.

std::vector< NDTCell * > lslgeneric::CellVector::getClosestNDTCells ( const pcl::PointXYZ &  point,
double &  radius 
)

Definition at line 220 of file cell_vector.cpp.

void lslgeneric::CellVector::getNeighbors ( const pcl::PointXYZ &  point,
const double &  radius,
std::vector< NDTCell * > &  cells 
) [virtual]

method to return all cells within a certain radius from a point

Implements lslgeneric::SpatialIndex.

Definition at line 142 of file cell_vector.cpp.

Definition at line 178 of file cell_vector.cpp.

int lslgeneric::CellVector::loadFromJFF ( FILE *  jffin)

Definition at line 267 of file cell_vector.cpp.

void lslgeneric::CellVector::setCellType ( NDTCell type) [virtual]

sets the cell factory type

Implements lslgeneric::SpatialIndex.

Definition at line 207 of file cell_vector.cpp.

int lslgeneric::CellVector::size ( ) [virtual]

Definition at line 115 of file cell_vector.cpp.


Member Data Documentation

Definition at line 89 of file cell_vector.h.

pcl::KdTreeFLANN<pcl::PointXYZ> lslgeneric::CellVector::meansTree [private]

Definition at line 91 of file cell_vector.h.

pcl::KdTree<pcl::PointXYZ>::PointCloudPtr lslgeneric::CellVector::mp [private]

Definition at line 92 of file cell_vector.h.

Definition at line 90 of file cell_vector.h.

Definition at line 93 of file cell_vector.h.


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


ndt_map
Author(s): Todor Stoyanov, Jari Saarinen, Henrik Andreasson
autogenerated on Wed Aug 26 2015 15:24:41