A spatial index represented as a grid map. More...
#include <lazy_grid.h>
Public Member Functions | |
virtual Cell< PointT > * | addPoint (const PointT &point) |
add a point and get back the pointer to the cell in which it ended up | |
virtual SpatialIndex< PointT > ::CellVectorItr | begin () |
iterator through all cells in index, points at the begining | |
virtual SpatialIndex< PointT > * | clone () const |
clone - create an empty object with same type | |
virtual SpatialIndex< PointT > * | copy () const |
copy - create the same object as a new instance | |
virtual SpatialIndex< PointT > ::CellVectorItr | end () |
iterator through all cells in index, points at the end | |
virtual void | getCellAt (int indX, int indY, int indZ, Cell< PointT > *&cell) |
virtual void | getCellAt (const PointT &pt, Cell< PointT > *&cell) |
virtual Cell< PointT > * | getCellForPoint (const PointT &point) |
void | getCellSize (double &cx, double &cy, double &cz) |
void | getCenter (double &cx, double &cy, double &cz) |
virtual std::vector< NDTCell < PointT > * > | getClosestCells (const PointT &pt) |
virtual NDTCell< PointT > * | getClosestNDTCell (const PointT &pt, bool checkForGaussian=true) |
virtual std::vector< NDTCell < PointT > * > | getClosestNDTCells (const PointT &pt, int &n_neigh, bool checkForGaussian=true) |
Cell< PointT > **** | getDataArrayPtr () |
void | getGridSize (int &cx, int &cy, int &cz) |
void | getGridSizeInMeters (double &cx, double &cy, double &cz) |
virtual void | getIndexForPoint (const PointT &pt, int &idx, int &idy, int &idz) |
virtual void | getNDTCellAt (int indX, int indY, int indZ, NDTCell< PointT > *&cell) |
virtual void | getNDTCellAt (const PointT &pt, NDTCell< PointT > *&cell) |
virtual void | getNeighbors (const PointT &point, const double &radius, std::vector< Cell< PointT > * > &cells) |
method to return all cells within a certain radius from a point | |
Cell< PointT > * | getProtoType () |
virtual void | initialize () |
virtual void | initializeAll () |
bool | isInside (const PointT &pt) |
LazyGrid (double cellSize) | |
LazyGrid (LazyGrid *prot) | |
LazyGrid (double sizeXmeters, double sizeYmeters, double sizeZmeters, double cellSizeX, double cellSizeY, double cellSizeZ, double _centerX, double _centerY, double _centerZ, Cell< PointT > *cellPrototype) | |
virtual int | loadFromJFF (FILE *jffin) |
reads map contents from .jff file | |
virtual void | setCellType (Cell< PointT > *type) |
sets the cell factory type | |
virtual void | setCenter (const double &cx, const double &cy, const double &cz) |
virtual void | setSize (const double &sx, const double &sy, const double &sz) |
virtual int | size () |
bool | traceLine (const Eigen::Vector3d &origin, const PointT &endpoint, const Eigen::Vector3d &diff, const double &maxz, std::vector< NDTCell< PointT > * > &cells) |
bool | traceLineWithEndpoint (const Eigen::Vector3d &origin, const PointT &endpoint, const Eigen::Vector3d &diff, const double &maxz, std::vector< NDTCell< PointT > * > &cells, Eigen::Vector3d &final_point) |
virtual | ~LazyGrid () |
Protected Member Functions | |
virtual bool | checkCellforNDT (int indX, int indY, int indZ, bool checkForGaussian=true) |
Protected Attributes | |
std::vector< Cell< PointT > * > | activeCells |
double | cellSizeX |
double | cellSizeY |
double | cellSizeZ |
bool | centerIsSet |
double | centerX |
double | centerY |
double | centerZ |
Cell< PointT > **** | dataArray |
bool | initialized |
Cell< PointT > * | protoType |
bool | sizeIsSet |
int | sizeX |
double | sizeXmeters |
int | sizeY |
double | sizeYmeters |
int | sizeZ |
double | sizeZmeters |
A spatial index represented as a grid map.
A grid map with delayed allocation of cells.
Definition at line 48 of file lazy_grid.h.
lslgeneric::LazyGrid< PointT >::LazyGrid | ( | double | cellSize | ) |
Definition at line 10 of file lazy_grid.hpp.
lslgeneric::LazyGrid< PointT >::LazyGrid | ( | LazyGrid< PointT > * | prot | ) |
lslgeneric::LazyGrid< PointT >::LazyGrid | ( | double | sizeXmeters, |
double | sizeYmeters, | ||
double | sizeZmeters, | ||
double | cellSizeX, | ||
double | cellSizeY, | ||
double | cellSizeZ, | ||
double | _centerX, | ||
double | _centerY, | ||
double | _centerZ, | ||
Cell< PointT > * | cellPrototype | ||
) |
Definition at line 45 of file lazy_grid.hpp.
lslgeneric::LazyGrid< PointT >::~LazyGrid | ( | ) | [virtual] |
Definition at line 164 of file lazy_grid.hpp.
Cell< PointT > * lslgeneric::LazyGrid< PointT >::addPoint | ( | const PointT & | point | ) | [virtual] |
add a point and get back the pointer to the cell in which it ended up
Implements lslgeneric::SpatialIndex< PointT >.
Definition at line 217 of file lazy_grid.hpp.
SpatialIndex< PointT >::CellVectorItr lslgeneric::LazyGrid< PointT >::begin | ( | ) | [virtual] |
iterator through all cells in index, points at the begining
Implements lslgeneric::SpatialIndex< PointT >.
Definition at line 285 of file lazy_grid.hpp.
bool lslgeneric::LazyGrid< PointT >::checkCellforNDT | ( | int | indX, |
int | indY, | ||
int | indZ, | ||
bool | checkForGaussian = true |
||
) | [protected, virtual] |
Definition at line 616 of file lazy_grid.hpp.
SpatialIndex< PointT > * lslgeneric::LazyGrid< PointT >::clone | ( | ) | const [virtual] |
clone - create an empty object with same type
Implements lslgeneric::SpatialIndex< PointT >.
Definition at line 303 of file lazy_grid.hpp.
SpatialIndex< PointT > * lslgeneric::LazyGrid< PointT >::copy | ( | ) | const [virtual] |
copy - create the same object as a new instance
Implements lslgeneric::SpatialIndex< PointT >.
Definition at line 309 of file lazy_grid.hpp.
SpatialIndex< PointT >::CellVectorItr lslgeneric::LazyGrid< PointT >::end | ( | ) | [virtual] |
iterator through all cells in index, points at the end
Implements lslgeneric::SpatialIndex< PointT >.
Definition at line 291 of file lazy_grid.hpp.
virtual void lslgeneric::LazyGrid< PointT >::getCellAt | ( | int | indX, |
int | indY, | ||
int | indZ, | ||
Cell< PointT > *& | cell | ||
) | [inline, virtual] |
Definition at line 86 of file lazy_grid.h.
virtual void lslgeneric::LazyGrid< PointT >::getCellAt | ( | const PointT & | pt, |
Cell< PointT > *& | cell | ||
) | [inline, virtual] |
Definition at line 94 of file lazy_grid.h.
Cell< PointT > * lslgeneric::LazyGrid< PointT >::getCellForPoint | ( | const PointT & | point | ) | [virtual] |
Implements lslgeneric::SpatialIndex< PointT >.
Definition at line 200 of file lazy_grid.hpp.
void lslgeneric::LazyGrid< PointT >::getCellSize | ( | double & | cx, |
double & | cy, | ||
double & | cz | ||
) |
Definition at line 662 of file lazy_grid.hpp.
void lslgeneric::LazyGrid< PointT >::getCenter | ( | double & | cx, |
double & | cy, | ||
double & | cz | ||
) |
Definition at line 670 of file lazy_grid.hpp.
std::vector< NDTCell< PointT > * > lslgeneric::LazyGrid< PointT >::getClosestCells | ( | const PointT & | pt | ) | [virtual] |
Definition at line 396 of file lazy_grid.hpp.
NDTCell< PointT > * lslgeneric::LazyGrid< PointT >::getClosestNDTCell | ( | const PointT & | pt, |
bool | checkForGaussian = true |
||
) | [virtual] |
Definition at line 527 of file lazy_grid.hpp.
std::vector< NDTCell< PointT > * > lslgeneric::LazyGrid< PointT >::getClosestNDTCells | ( | const PointT & | pt, |
int & | n_neigh, | ||
bool | checkForGaussian = true |
||
) | [virtual] |
Definition at line 429 of file lazy_grid.hpp.
Cell<PointT>**** lslgeneric::LazyGrid< PointT >::getDataArrayPtr | ( | ) | [inline] |
Definition at line 127 of file lazy_grid.h.
void lslgeneric::LazyGrid< PointT >::getGridSize | ( | int & | cx, |
int & | cy, | ||
int & | cz | ||
) |
Definition at line 679 of file lazy_grid.hpp.
void lslgeneric::LazyGrid< PointT >::getGridSizeInMeters | ( | double & | cx, |
double & | cy, | ||
double & | cz | ||
) |
Definition at line 687 of file lazy_grid.hpp.
void lslgeneric::LazyGrid< PointT >::getIndexForPoint | ( | const PointT & | pt, |
int & | idx, | ||
int & | idy, | ||
int & | idz | ||
) | [inline, virtual] |
Definition at line 357 of file lazy_grid.hpp.
virtual void lslgeneric::LazyGrid< PointT >::getNDTCellAt | ( | int | indX, |
int | indY, | ||
int | indZ, | ||
NDTCell< PointT > *& | cell | ||
) | [inline, virtual] |
Definition at line 99 of file lazy_grid.h.
virtual void lslgeneric::LazyGrid< PointT >::getNDTCellAt | ( | const PointT & | pt, |
NDTCell< PointT > *& | cell | ||
) | [inline, virtual] |
Definition at line 106 of file lazy_grid.h.
void lslgeneric::LazyGrid< PointT >::getNeighbors | ( | const PointT & | point, |
const double & | radius, | ||
std::vector< Cell< PointT > * > & | cells | ||
) | [virtual] |
method to return all cells within a certain radius from a point
Implements lslgeneric::SpatialIndex< PointT >.
Definition at line 328 of file lazy_grid.hpp.
Cell<PointT>* lslgeneric::LazyGrid< PointT >::getProtoType | ( | ) | [inline] |
Definition at line 118 of file lazy_grid.h.
void lslgeneric::LazyGrid< PointT >::initialize | ( | ) | [virtual] |
Definition at line 142 of file lazy_grid.hpp.
void lslgeneric::LazyGrid< PointT >::initializeAll | ( | ) | [virtual] |
Definition at line 107 of file lazy_grid.hpp.
bool lslgeneric::LazyGrid< PointT >::isInside | ( | const PointT & | pt | ) | [inline] |
Definition at line 136 of file lazy_grid.h.
int lslgeneric::LazyGrid< PointT >::loadFromJFF | ( | FILE * | jffin | ) | [virtual] |
reads map contents from .jff file
Definition at line 695 of file lazy_grid.hpp.
void lslgeneric::LazyGrid< PointT >::setCellType | ( | Cell< PointT > * | type | ) | [virtual] |
sets the cell factory type
Implements lslgeneric::SpatialIndex< PointT >.
Definition at line 638 of file lazy_grid.hpp.
void lslgeneric::LazyGrid< PointT >::setCenter | ( | const double & | cx, |
const double & | cy, | ||
const double & | cz | ||
) | [virtual] |
the following methods provide index specific functionalities and don't have to be implemented by all sub-classes
Reimplemented from lslgeneric::SpatialIndex< PointT >.
Definition at line 74 of file lazy_grid.hpp.
void lslgeneric::LazyGrid< PointT >::setSize | ( | const double & | sx, |
const double & | sy, | ||
const double & | sz | ||
) | [virtual] |
Reimplemented from lslgeneric::SpatialIndex< PointT >.
Definition at line 88 of file lazy_grid.hpp.
int lslgeneric::LazyGrid< PointT >::size | ( | void | ) | [virtual] |
Definition at line 297 of file lazy_grid.hpp.
bool lslgeneric::LazyGrid< PointT >::traceLine | ( | const Eigen::Vector3d & | origin, |
const PointT & | endpoint, | ||
const Eigen::Vector3d & | diff, | ||
const double & | maxz, | ||
std::vector< NDTCell< PointT > * > & | cells | ||
) | [inline] |
Select the smallest resolution
We only want to check every cell once, so increase the index if we are still in the same cell
Add fake point to initialize!
Definition at line 797 of file lazy_grid.hpp.
bool lslgeneric::LazyGrid< PointT >::traceLineWithEndpoint | ( | const Eigen::Vector3d & | origin, |
const PointT & | endpoint, | ||
const Eigen::Vector3d & | diff, | ||
const double & | maxz, | ||
std::vector< NDTCell< PointT > * > & | cells, | ||
Eigen::Vector3d & | final_point | ||
) | [inline] |
Select the smallest resolution
We only want to check every cell once, so increase the index if we are still in the same cell
Add fake point to initialize!
Definition at line 866 of file lazy_grid.hpp.
std::vector<Cell<PointT>*> lslgeneric::LazyGrid< PointT >::activeCells [protected] |
Definition at line 146 of file lazy_grid.h.
double lslgeneric::LazyGrid< PointT >::cellSizeX [protected] |
Definition at line 152 of file lazy_grid.h.
double lslgeneric::LazyGrid< PointT >::cellSizeY [protected] |
Definition at line 152 of file lazy_grid.h.
double lslgeneric::LazyGrid< PointT >::cellSizeZ [protected] |
Definition at line 152 of file lazy_grid.h.
bool lslgeneric::LazyGrid< PointT >::centerIsSet [protected] |
Definition at line 148 of file lazy_grid.h.
double lslgeneric::LazyGrid< PointT >::centerX [protected] |
Definition at line 153 of file lazy_grid.h.
double lslgeneric::LazyGrid< PointT >::centerY [protected] |
Definition at line 153 of file lazy_grid.h.
double lslgeneric::LazyGrid< PointT >::centerZ [protected] |
Definition at line 153 of file lazy_grid.h.
Cell<PointT>**** lslgeneric::LazyGrid< PointT >::dataArray [protected] |
Definition at line 143 of file lazy_grid.h.
bool lslgeneric::LazyGrid< PointT >::initialized [protected] |
Definition at line 142 of file lazy_grid.h.
Cell<PointT>* lslgeneric::LazyGrid< PointT >::protoType [protected] |
Definition at line 145 of file lazy_grid.h.
bool lslgeneric::LazyGrid< PointT >::sizeIsSet [protected] |
Definition at line 148 of file lazy_grid.h.
int lslgeneric::LazyGrid< PointT >::sizeX [protected] |
Definition at line 154 of file lazy_grid.h.
double lslgeneric::LazyGrid< PointT >::sizeXmeters [protected] |
Definition at line 151 of file lazy_grid.h.
int lslgeneric::LazyGrid< PointT >::sizeY [protected] |
Definition at line 154 of file lazy_grid.h.
double lslgeneric::LazyGrid< PointT >::sizeYmeters [protected] |
Definition at line 151 of file lazy_grid.h.
int lslgeneric::LazyGrid< PointT >::sizeZ [protected] |
Definition at line 154 of file lazy_grid.h.
double lslgeneric::LazyGrid< PointT >::sizeZmeters [protected] |
Definition at line 151 of file lazy_grid.h.