, including all inherited members.
| addPoint(pcl::PointXYZ &pt) | lslgeneric::NDTCell | [inline, virtual] |
| addPoints(pcl::PointCloud< pcl::PointXYZ > &pt) | lslgeneric::NDTCell | [inline, virtual] |
| B | lslgeneric::NDTCell | [private] |
| CellClass enum name | lslgeneric::NDTCell | |
| center_ | lslgeneric::NDTCell | [private] |
| cl_ | lslgeneric::NDTCell | [private] |
| classify() | lslgeneric::NDTCell | |
| clone() const | lslgeneric::NDTCell | [virtual] |
| computeGaussian(int mode=CELL_UPDATE_MODE_SAMPLE_VARIANCE, unsigned int maxnumpoints=1e9, float occupancy_limit=255, Eigen::Vector3d origin=Eigen::Vector3d(0, 0, 0), double sensor_noise=0.1) | lslgeneric::NDTCell | |
| computeGaussianSimple() | lslgeneric::NDTCell | |
| computeMaximumLikelihoodAlongLine(const pcl::PointXYZ &p1, const pcl::PointXYZ &p2, Eigen::Vector3d &out) | lslgeneric::NDTCell | |
| consistency_score | lslgeneric::NDTCell | |
| copy() const | lslgeneric::NDTCell | [virtual] |
| cost | lslgeneric::NDTCell | |
| cov_ | lslgeneric::NDTCell | [private] |
| d1_ | lslgeneric::NDTCell | [private] |
| d2_ | lslgeneric::NDTCell | [private] |
| edata | lslgeneric::NDTCell | [private] |
| emptydist | lslgeneric::NDTCell | [private] |
| emptylik | lslgeneric::NDTCell | [private] |
| emptyval | lslgeneric::NDTCell | [private] |
| EVAL_FACTOR | lslgeneric::NDTCell | [private, static] |
| EVAL_ROUGH_THR | lslgeneric::NDTCell | [private, static] |
| evals_ | lslgeneric::NDTCell | [private] |
| EVEC_INCLINED_THR | lslgeneric::NDTCell | [private, static] |
| evecs_ | lslgeneric::NDTCell | [private] |
| G | lslgeneric::NDTCell | [private] |
| getCenter() const | lslgeneric::NDTCell | [inline] |
| getClass() const | lslgeneric::NDTCell | [inline] |
| getCov() const | lslgeneric::NDTCell | [inline] |
| getDiagonal() const | lslgeneric::NDTCell | [inline, virtual] |
| getDimensions(double &xs, double &ys, double &zs) const | lslgeneric::NDTCell | [inline] |
| getDynamicLikelihood(unsigned int N) | lslgeneric::NDTCell | [inline] |
| getEmptyval() | lslgeneric::NDTCell | [inline] |
| getEvals() const | lslgeneric::NDTCell | [inline] |
| getEvecs() const | lslgeneric::NDTCell | [inline] |
| getEventData() | lslgeneric::NDTCell | [inline] |
| getInverseCov() const | lslgeneric::NDTCell | [inline] |
| getLikelihood(const pcl::PointXYZ &pt) const | lslgeneric::NDTCell | |
| getMean() const | lslgeneric::NDTCell | [inline] |
| getN() | lslgeneric::NDTCell | [inline] |
| getOccupancy() | lslgeneric::NDTCell | [inline] |
| getOccupancyRescaled() | lslgeneric::NDTCell | [inline] |
| getRGB(float &r, float &g, float &b) | lslgeneric::NDTCell | [inline] |
| hasGaussian_ | lslgeneric::NDTCell | |
| HORIZONTAL enum value | lslgeneric::NDTCell | |
| icov_ | lslgeneric::NDTCell | [private] |
| INCLINED enum value | lslgeneric::NDTCell | |
| isEmpty | lslgeneric::NDTCell | |
| isInside(const pcl::PointXYZ pt) const | lslgeneric::NDTCell | [inline] |
| loadFromJFF(FILE *jffin) | lslgeneric::NDTCell | |
| loadJFFEventData(FILE *jffin, TEventData &evdata) | lslgeneric::NDTCell | [private] |
| loadJFFMatrix(FILE *jffin, Eigen::Matrix3d &mat) | lslgeneric::NDTCell | [private] |
| loadJFFVector(FILE *jffin, Eigen::Vector3d &vec) | lslgeneric::NDTCell | [private] |
| max_occu_ | lslgeneric::NDTCell | [private] |
| mean_ | lslgeneric::NDTCell | [private] |
| N | lslgeneric::NDTCell | [private] |
| NDTCell() | lslgeneric::NDTCell | [inline] |
| NDTCell(pcl::PointXYZ ¢er, double &xsize, double &ysize, double &zsize) | lslgeneric::NDTCell | [inline] |
| NDTCell(const NDTCell &other) | lslgeneric::NDTCell | [inline] |
| occ | lslgeneric::NDTCell | [private] |
| parametersSet_ | lslgeneric::NDTCell | [private, static] |
| points_ | lslgeneric::NDTCell | |
| R | lslgeneric::NDTCell | [private] |
| rescaleCovariance() | lslgeneric::NDTCell | |
| rescaleCovariance(Eigen::Matrix3d &cov, Eigen::Matrix3d &invCov) | lslgeneric::NDTCell | |
| ROUGH enum value | lslgeneric::NDTCell | |
| setCenter(const pcl::PointXYZ &cn) | lslgeneric::NDTCell | [inline] |
| setCov(const Eigen::Matrix3d &cov) | lslgeneric::NDTCell | |
| setDimensions(const double &xs, const double &ys, const double &zs) | lslgeneric::NDTCell | [inline] |
| setEmptyval(int emptyval_) | lslgeneric::NDTCell | [inline] |
| setEvals(const Eigen::Vector3d &ev) | lslgeneric::NDTCell | [inline] |
| setEventData(TEventData _ed) | lslgeneric::NDTCell | [inline] |
| setMean(const Eigen::Vector3d &mean) | lslgeneric::NDTCell | [inline] |
| setN(int N_) | lslgeneric::NDTCell | [inline] |
| setOccupancy(float occ_) | lslgeneric::NDTCell | [inline] |
| setParameters(double _EVAL_ROUGH_THR=0.1, double _EVEC_INCLINED_THR=8 *M_PI/18, double _EVAL_FACTOR=100) | lslgeneric::NDTCell | [static] |
| setRGB(float r, float g, float b) | lslgeneric::NDTCell | [inline] |
| squareSum(const Eigen::Matrix3d &C, const Eigen::Vector3d &x) | lslgeneric::NDTCell | [inline, private] |
| studentT() | lslgeneric::NDTCell | [private] |
| UNKNOWN enum value | lslgeneric::NDTCell | |
| updateColorInformation() | lslgeneric::NDTCell | |
| updateEmpty(double elik, double dist) | lslgeneric::NDTCell | [inline] |
| updateOccupancy(float occ_val, float max_occu=255.0) | lslgeneric::NDTCell | [inline] |
| updateSampleVariance(const Eigen::Matrix3d &cov2, const Eigen::Vector3d &m2, unsigned int numpointsindistribution, bool updateOccupancyFlag=true, float max_occu=1024, unsigned int maxnumpoints=1e9) | lslgeneric::NDTCell | |
| VERTICAL enum value | lslgeneric::NDTCell | |
| writeJFFEventData(FILE *jffout, TEventData &evdata) | lslgeneric::NDTCell | [private] |
| writeJFFMatrix(FILE *jffout, Eigen::Matrix3d &mat) | lslgeneric::NDTCell | [private] |
| writeJFFVector(FILE *jffout, Eigen::Vector3d &vec) | lslgeneric::NDTCell | [private] |
| writeToJFF(FILE *jffout) | lslgeneric::NDTCell | |
| xsize_ | lslgeneric::NDTCell | [private] |
| ysize_ | lslgeneric::NDTCell | [private] |
| zsize_ | lslgeneric::NDTCell | [private] |
| ~NDTCell() | lslgeneric::NDTCell | [inline, virtual] |