Implements an NDT based spatial index. More...
#include <ndt_occupancy_map.h>
Public Member Functions | |
void | addPointCloud (const Eigen::Vector3d &origin, const pcl::PointCloud< PointT > &pc) |
void | computeNDTCells (int cellupdatemode=CELL_UPDATE_MODE_SAMPLE_VARIANCE_WITH_RESET) |
void | debugToVRML (const char *fname, pcl::PointCloud< PointT > &pc) |
std::vector < lslgeneric::NDTCell< PointT > * > | getAllCells () |
bool | getCellForPoint (const PointT &refPoint, NDTCell< PointT > *&cell) |
NDTCell< PointT > * | getCellIdx (unsigned int idx) |
return the cell using a specific index (not available for all spatialindexes), will return NULL if the idx is not valid. | |
std::vector< NDTCell< PointT > * > | getCellsForPoint (const PointT pt, double radius) |
std::vector < lslgeneric::NDTCell< PointT > * > | getDynamicCells (unsigned int Timescale, float threshold) |
double | getLikelihoodForPoint (PointT pt) |
SpatialIndex< PointT > * | getMyIndex () const |
std::string | getMyIndexStr () const |
return the spatial index used as a string | |
void | loadDepthImage (const cv::Mat &depthImage, DepthCamera< PointT > &cameraParams) |
pcl::PointCloud< PointT > | loadDepthImageFeatures (const cv::Mat &depthImage, std::vector< cv::KeyPoint > &keypoints, size_t &supportSize, double maxVar, DepthCamera< PointT > &cameraParams, bool estimateParamsDI=false, bool nonMean=false) |
void | loadPointCloud (const pcl::PointCloud< PointT > &pc, const std::vector< std::vector< size_t > > &indices) |
each entry in the indices vector contains a set of indices to a NDC cell. | |
NDTOccupancyMap () | |
NDTOccupancyMap (SpatialIndex< PointT > *idx, float _resolution) | |
NDTOccupancyMap (const NDTOccupancyMap &other) | |
int | numberOfActiveCells () |
std::vector< NDTCell< PointT > * > | pseudoTransformNDT (Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > T) |
void | writeToVRML (const char *filename) |
virtual void | writeToVRML (FILE *fout) |
virtual void | writeToVRML (FILE *fout, Eigen::Vector3d col) |
virtual | ~NDTOccupancyMap () |
Protected Member Functions | |
void | loadPointCloud (const Eigen::Vector3d &origin, const pcl::PointCloud< PointT > &pc) |
Protected Attributes | |
SpatialIndex< PointT > * | index_ |
bool | isFirstLoad_ |
float | resolution |
Implements an NDT based spatial index.
This is an interface to a SpatialIndex (custom defined) that contains NDT cells. Provides methods to create from a PointCloud
Definition at line 62 of file ndt_occupancy_map.h.
lslgeneric::NDTOccupancyMap< PointT >::NDTOccupancyMap | ( | ) | [inline] |
Definition at line 66 of file ndt_occupancy_map.h.
lslgeneric::NDTOccupancyMap< PointT >::NDTOccupancyMap | ( | SpatialIndex< PointT > * | idx, |
float | _resolution | ||
) | [inline] |
default constructor. The SpatialIndex sent as a paramter is used as a factory every time that loadPointCloud is called. it can/should be deallocated outside the class after the destruction of the NDTMap
Definition at line 74 of file ndt_occupancy_map.h.
lslgeneric::NDTOccupancyMap< PointT >::NDTOccupancyMap | ( | const NDTOccupancyMap< PointT > & | other | ) | [inline] |
Definition at line 84 of file ndt_occupancy_map.h.
virtual lslgeneric::NDTOccupancyMap< PointT >::~NDTOccupancyMap | ( | ) | [inline, virtual] |
Definition at line 96 of file ndt_occupancy_map.h.
void lslgeneric::NDTOccupancyMap< PointT >::addPointCloud | ( | const Eigen::Vector3d & | origin, |
const pcl::PointCloud< PointT > & | pc | ||
) |
Add new pointcloud to map
&origin | is the position of the sensor, from where the scan has been taken from. |
&pc | is the pointcloud to be added |
Adds a new cloud - NOTE::highly Experimental
Definition at line 167 of file ndt_occupancy_map.hpp.
void lslgeneric::NDTOccupancyMap< PointT >::computeNDTCells | ( | int | cellupdatemode = CELL_UPDATE_MODE_SAMPLE_VARIANCE_WITH_RESET | ) |
Helper function, computes the NDTCells
Definition at line 352 of file ndt_occupancy_map.hpp.
void lslgeneric::NDTOccupancyMap< PointT >::debugToVRML | ( | const char * | fname, |
pcl::PointCloud< PointT > & | pc | ||
) |
Definition at line 822 of file ndt_occupancy_map.hpp.
std::vector< lslgeneric::NDTCell< PointT > * > lslgeneric::NDTOccupancyMap< PointT >::getAllCells | ( | ) |
Returns all computed cells from the map
Definition at line 942 of file ndt_occupancy_map.hpp.
bool lslgeneric::NDTOccupancyMap< PointT >::getCellForPoint | ( | const PointT & | refPoint, |
NDTCell< PointT > *& | cell | ||
) |
Definition at line 732 of file ndt_occupancy_map.hpp.
NDTCell< PointT > * lslgeneric::NDTOccupancyMap< PointT >::getCellIdx | ( | unsigned int | idx | ) |
return the cell using a specific index (not available for all spatialindexes), will return NULL if the idx is not valid.
Definition at line 900 of file ndt_occupancy_map.hpp.
std::vector< NDTCell< PointT > * > lslgeneric::NDTOccupancyMap< PointT >::getCellsForPoint | ( | const PointT | pt, |
double | radius | ||
) |
Definition at line 711 of file ndt_occupancy_map.hpp.
std::vector< lslgeneric::NDTCell< PointT > * > lslgeneric::NDTOccupancyMap< PointT >::getDynamicCells | ( | unsigned int | Timescale, |
float | threshold | ||
) |
Returns all computed cells from the map
Returns dynamic cells from the map
Definition at line 915 of file ndt_occupancy_map.hpp.
double lslgeneric::NDTOccupancyMap< PointT >::getLikelihoodForPoint | ( | PointT | pt | ) |
Definition at line 514 of file ndt_occupancy_map.hpp.
SpatialIndex<PointT>* lslgeneric::NDTOccupancyMap< PointT >::getMyIndex | ( | ) | const [inline] |
Definition at line 133 of file ndt_occupancy_map.h.
std::string lslgeneric::NDTOccupancyMap< PointT >::getMyIndexStr | ( | ) | const |
return the spatial index used as a string
returns the current spatial index as a string (debugging function)
Definition at line 491 of file ndt_occupancy_map.hpp.
void lslgeneric::NDTOccupancyMap< PointT >::loadDepthImage | ( | const cv::Mat & | depthImage, |
DepthCamera< PointT > & | cameraParams | ||
) |
Definition at line 246 of file ndt_occupancy_map.hpp.
pcl::PointCloud< PointT > lslgeneric::NDTOccupancyMap< PointT >::loadDepthImageFeatures | ( | const cv::Mat & | depthImage, |
std::vector< cv::KeyPoint > & | keypoints, | ||
size_t & | supportSize, | ||
double | maxVar, | ||
DepthCamera< PointT > & | cameraParams, | ||
bool | estimateParamsDI = false , |
||
bool | nonMean = false |
||
) |
Definition at line 254 of file ndt_occupancy_map.hpp.
void lslgeneric::NDTOccupancyMap< PointT >::loadPointCloud | ( | const pcl::PointCloud< PointT > & | pc, |
const std::vector< std::vector< size_t > > & | indices | ||
) |
each entry in the indices vector contains a set of indices to a NDC cell.
These load methods are not currently supported by the NDTOccupancyMap!
Definition at line 225 of file ndt_occupancy_map.hpp.
void lslgeneric::NDTOccupancyMap< PointT >::loadPointCloud | ( | const Eigen::Vector3d & | origin, |
const pcl::PointCloud< PointT > & | pc | ||
) | [protected] |
Main implemented method for now. Loads a single point cloud into an NDTOccupancyMap.
Definition at line 18 of file ndt_occupancy_map.hpp.
int lslgeneric::NDTOccupancyMap< PointT >::numberOfActiveCells | ( | ) |
Definition at line 967 of file ndt_occupancy_map.hpp.
std::vector< NDTCell< PointT > * > lslgeneric::NDTOccupancyMap< PointT >::pseudoTransformNDT | ( | Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > | T | ) |
Definition at line 867 of file ndt_occupancy_map.hpp.
void lslgeneric::NDTOccupancyMap< PointT >::writeToVRML | ( | const char * | filename | ) |
output method, saves as vrml the oct tree and all the ellipsoids
Definition at line 402 of file ndt_occupancy_map.hpp.
void lslgeneric::NDTOccupancyMap< PointT >::writeToVRML | ( | FILE * | fout | ) | [virtual] |
helper output method
Definition at line 438 of file ndt_occupancy_map.hpp.
void lslgeneric::NDTOccupancyMap< PointT >::writeToVRML | ( | FILE * | fout, |
Eigen::Vector3d | col | ||
) | [virtual] |
Definition at line 465 of file ndt_occupancy_map.hpp.
SpatialIndex<PointT>* lslgeneric::NDTOccupancyMap< PointT >::index_ [protected] |
Definition at line 168 of file ndt_occupancy_map.h.
bool lslgeneric::NDTOccupancyMap< PointT >::isFirstLoad_ [protected] |
Definition at line 169 of file ndt_occupancy_map.h.
float lslgeneric::NDTOccupancyMap< PointT >::resolution [protected] |
Definition at line 171 of file ndt_occupancy_map.h.