A spatial index represented as a grid map. More...
#include <lazy_grid.h>
Public Member Functions | |
virtual NDTCell * | addPoint (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 | |
virtual SpatialIndex * | clone () const |
clone - create an empty object with same type | |
virtual SpatialIndex * | copy () 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 void | getCellAt (int indX, int indY, int indZ, NDTCell *&cell) |
virtual void | getCellAt (const pcl::PointXYZ &pt, NDTCell *&cell) |
virtual NDTCell * | getCellForPoint (const pcl::PointXYZ &point) |
void | getCellSize (double &cx, double &cy, double &cz) |
void | getCenter (double &cx, double &cy, double &cz) |
virtual std::vector< NDTCell * > | getClosestCells (const pcl::PointXYZ &pt) |
virtual NDTCell * | getClosestNDTCell (const pcl::PointXYZ &pt, bool checkForGaussian=true) |
virtual std::vector< NDTCell * > | getClosestNDTCells (const pcl::PointXYZ &pt, int &n_neigh, bool checkForGaussian=true) |
NDTCell **** | getDataArrayPtr () |
void | getGridSize (int &cx, int &cy, int &cz) |
void | getGridSizeInMeters (double &cx, double &cy, double &cz) |
virtual void | getIndexForPoint (const pcl::PointXYZ &pt, int &idx, int &idy, int &idz) |
virtual void | getNDTCellAt (int indX, int indY, int indZ, NDTCell *&cell) |
virtual void | getNDTCellAt (const pcl::PointXYZ &pt, NDTCell *&cell) |
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 | |
NDTCell * | getProtoType () |
virtual void | initialize () |
virtual void | initializeAll () |
bool | isInside (const pcl::PointXYZ &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, NDTCell *cellPrototype) | |
virtual int | loadFromJFF (FILE *jffin) |
reads map contents from .jff file | |
virtual void | setCellType (NDTCell *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 pcl::PointXYZ &endpoint, const Eigen::Vector3d &diff, const double &maxz, std::vector< NDTCell * > &cells) |
bool | traceLineWithEndpoint (const Eigen::Vector3d &origin, const pcl::PointXYZ &endpoint, const Eigen::Vector3d &diff, const double &maxz, std::vector< NDTCell * > &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< NDTCell * > | activeCells |
double | cellSizeX |
double | cellSizeY |
double | cellSizeZ |
bool | centerIsSet |
double | centerX |
double | centerY |
double | centerZ |
NDTCell **** | dataArray |
bool | initialized |
NDTCell * | 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 47 of file lazy_grid.h.
lslgeneric::LazyGrid::LazyGrid | ( | double | cellSize | ) |
Definition at line 10 of file lazy_grid.cpp.
lslgeneric::LazyGrid::LazyGrid | ( | LazyGrid * | prot | ) |
Definition at line 19 of file lazy_grid.cpp.
lslgeneric::LazyGrid::LazyGrid | ( | double | sizeXmeters, |
double | sizeYmeters, | ||
double | sizeZmeters, | ||
double | cellSizeX, | ||
double | cellSizeY, | ||
double | cellSizeZ, | ||
double | _centerX, | ||
double | _centerY, | ||
double | _centerZ, | ||
NDTCell * | cellPrototype | ||
) |
Definition at line 43 of file lazy_grid.cpp.
lslgeneric::LazyGrid::~LazyGrid | ( | ) | [virtual] |
Definition at line 151 of file lazy_grid.cpp.
NDTCell * lslgeneric::LazyGrid::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 199 of file lazy_grid.cpp.
SpatialIndex::CellVectorItr lslgeneric::LazyGrid::begin | ( | ) | [virtual] |
iterator through all cells in index, points at the begining
Implements lslgeneric::SpatialIndex.
Definition at line 251 of file lazy_grid.cpp.
bool lslgeneric::LazyGrid::checkCellforNDT | ( | int | indX, |
int | indY, | ||
int | indZ, | ||
bool | checkForGaussian = true |
||
) | [protected, virtual] |
Definition at line 449 of file lazy_grid.cpp.
SpatialIndex * lslgeneric::LazyGrid::clone | ( | ) | const [virtual] |
clone - create an empty object with same type
Implements lslgeneric::SpatialIndex.
Definition at line 266 of file lazy_grid.cpp.
SpatialIndex * lslgeneric::LazyGrid::copy | ( | ) | const [virtual] |
copy - create the same object as a new instance
Implements lslgeneric::SpatialIndex.
Definition at line 271 of file lazy_grid.cpp.
SpatialIndex::CellVectorItr lslgeneric::LazyGrid::end | ( | ) | [virtual] |
iterator through all cells in index, points at the end
Implements lslgeneric::SpatialIndex.
Definition at line 256 of file lazy_grid.cpp.
virtual void lslgeneric::LazyGrid::getCellAt | ( | int | indX, |
int | indY, | ||
int | indZ, | ||
NDTCell *& | cell | ||
) | [inline, virtual] |
Definition at line 85 of file lazy_grid.h.
virtual void lslgeneric::LazyGrid::getCellAt | ( | const pcl::PointXYZ & | pt, |
NDTCell *& | cell | ||
) | [inline, virtual] |
Definition at line 93 of file lazy_grid.h.
NDTCell * lslgeneric::LazyGrid::getCellForPoint | ( | const pcl::PointXYZ & | point | ) | [virtual] |
Implements lslgeneric::SpatialIndex.
Definition at line 183 of file lazy_grid.cpp.
void lslgeneric::LazyGrid::getCellSize | ( | double & | cx, |
double & | cy, | ||
double & | cz | ||
) |
Definition at line 474 of file lazy_grid.cpp.
void lslgeneric::LazyGrid::getCenter | ( | double & | cx, |
double & | cy, | ||
double & | cz | ||
) |
Definition at line 481 of file lazy_grid.cpp.
std::vector< NDTCell * > lslgeneric::LazyGrid::getClosestCells | ( | const pcl::PointXYZ & | pt | ) | [virtual] |
Definition at line 323 of file lazy_grid.cpp.
NDTCell * lslgeneric::LazyGrid::getClosestNDTCell | ( | const pcl::PointXYZ & | pt, |
bool | checkForGaussian = true |
||
) | [virtual] |
Definition at line 387 of file lazy_grid.cpp.
std::vector< NDTCell * > lslgeneric::LazyGrid::getClosestNDTCells | ( | const pcl::PointXYZ & | pt, |
int & | n_neigh, | ||
bool | checkForGaussian = true |
||
) | [virtual] |
Definition at line 353 of file lazy_grid.cpp.
NDTCell**** lslgeneric::LazyGrid::getDataArrayPtr | ( | ) | [inline] |
Definition at line 125 of file lazy_grid.h.
void lslgeneric::LazyGrid::getGridSize | ( | int & | cx, |
int & | cy, | ||
int & | cz | ||
) |
Definition at line 489 of file lazy_grid.cpp.
void lslgeneric::LazyGrid::getGridSizeInMeters | ( | double & | cx, |
double & | cy, | ||
double & | cz | ||
) |
Definition at line 496 of file lazy_grid.cpp.
void lslgeneric::LazyGrid::getIndexForPoint | ( | const pcl::PointXYZ & | pt, |
int & | idx, | ||
int & | idy, | ||
int & | idz | ||
) | [virtual] |
Definition at line 316 of file lazy_grid.cpp.
virtual void lslgeneric::LazyGrid::getNDTCellAt | ( | int | indX, |
int | indY, | ||
int | indZ, | ||
NDTCell *& | cell | ||
) | [inline, virtual] |
Definition at line 99 of file lazy_grid.h.
virtual void lslgeneric::LazyGrid::getNDTCellAt | ( | const pcl::PointXYZ & | pt, |
NDTCell *& | cell | ||
) | [inline, virtual] |
Definition at line 106 of file lazy_grid.h.
void lslgeneric::LazyGrid::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 289 of file lazy_grid.cpp.
NDTCell* lslgeneric::LazyGrid::getProtoType | ( | ) | [inline] |
Definition at line 117 of file lazy_grid.h.
void lslgeneric::LazyGrid::initialize | ( | ) | [virtual] |
Definition at line 134 of file lazy_grid.cpp.
void lslgeneric::LazyGrid::initializeAll | ( | ) | [virtual] |
Definition at line 102 of file lazy_grid.cpp.
bool lslgeneric::LazyGrid::isInside | ( | const pcl::PointXYZ & | pt | ) | [inline] |
Definition at line 134 of file lazy_grid.h.
int lslgeneric::LazyGrid::loadFromJFF | ( | FILE * | jffin | ) | [virtual] |
reads map contents from .jff file
Definition at line 503 of file lazy_grid.cpp.
void lslgeneric::LazyGrid::setCellType | ( | NDTCell * | type | ) | [virtual] |
sets the cell factory type
Implements lslgeneric::SpatialIndex.
Definition at line 466 of file lazy_grid.cpp.
void lslgeneric::LazyGrid::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.
Definition at line 71 of file lazy_grid.cpp.
void lslgeneric::LazyGrid::setSize | ( | const double & | sx, |
const double & | sy, | ||
const double & | sz | ||
) | [virtual] |
Reimplemented from lslgeneric::SpatialIndex.
Definition at line 84 of file lazy_grid.cpp.
int lslgeneric::LazyGrid::size | ( | ) | [virtual] |
Definition at line 261 of file lazy_grid.cpp.
bool lslgeneric::LazyGrid::traceLine | ( | const Eigen::Vector3d & | origin, |
const pcl::PointXYZ & | endpoint, | ||
const Eigen::Vector3d & | diff, | ||
const double & | maxz, | ||
std::vector< NDTCell * > & | cells | ||
) |
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 607 of file lazy_grid.cpp.
bool lslgeneric::LazyGrid::traceLineWithEndpoint | ( | const Eigen::Vector3d & | origin, |
const pcl::PointXYZ & | endpoint, | ||
const Eigen::Vector3d & | diff, | ||
const double & | maxz, | ||
std::vector< NDTCell * > & | cells, | ||
Eigen::Vector3d & | final_point | ||
) |
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 674 of file lazy_grid.cpp.
std::vector<NDTCell*> lslgeneric::LazyGrid::activeCells [protected] |
Definition at line 144 of file lazy_grid.h.
double lslgeneric::LazyGrid::cellSizeX [protected] |
Definition at line 148 of file lazy_grid.h.
double lslgeneric::LazyGrid::cellSizeY [protected] |
Definition at line 148 of file lazy_grid.h.
double lslgeneric::LazyGrid::cellSizeZ [protected] |
Definition at line 148 of file lazy_grid.h.
bool lslgeneric::LazyGrid::centerIsSet [protected] |
Definition at line 145 of file lazy_grid.h.
double lslgeneric::LazyGrid::centerX [protected] |
Definition at line 149 of file lazy_grid.h.
double lslgeneric::LazyGrid::centerY [protected] |
Definition at line 149 of file lazy_grid.h.
double lslgeneric::LazyGrid::centerZ [protected] |
Definition at line 149 of file lazy_grid.h.
NDTCell**** lslgeneric::LazyGrid::dataArray [protected] |
Definition at line 141 of file lazy_grid.h.
bool lslgeneric::LazyGrid::initialized [protected] |
Definition at line 140 of file lazy_grid.h.
NDTCell* lslgeneric::LazyGrid::protoType [protected] |
Definition at line 143 of file lazy_grid.h.
bool lslgeneric::LazyGrid::sizeIsSet [protected] |
Definition at line 145 of file lazy_grid.h.
int lslgeneric::LazyGrid::sizeX [protected] |
Definition at line 150 of file lazy_grid.h.
double lslgeneric::LazyGrid::sizeXmeters [protected] |
Definition at line 147 of file lazy_grid.h.
int lslgeneric::LazyGrid::sizeY [protected] |
Definition at line 150 of file lazy_grid.h.
double lslgeneric::LazyGrid::sizeYmeters [protected] |
Definition at line 147 of file lazy_grid.h.
int lslgeneric::LazyGrid::sizeZ [protected] |
Definition at line 150 of file lazy_grid.h.
double lslgeneric::LazyGrid::sizeZmeters [protected] |
Definition at line 147 of file lazy_grid.h.