Implements an NDT based spatial index. More...
#include <ndt_map.h>
Public Member Functions | |
void | addDistributionToCell (const Eigen::Matrix3d &ucov, const Eigen::Vector3d &umean, unsigned int numpointsindistribution, float r=0, float g=0, float b=0, unsigned int maxnumpoints=1e9, float max_occupancy=1024) |
virtual bool | addMeasurement (const Eigen::Vector3d &origin, PointT endpoint, double classifierTh, double maxz, double sensor_noise) |
virtual void | addPointCloud (const Eigen::Vector3d &origin, const pcl::PointCloud< PointT > &pc, double classifierTh=0.06, double maxz=100.0, double sensor_noise=0.25, double occupancy_limit=255) |
virtual void | addPointCloudMeanUpdate (const Eigen::Vector3d &origin, const pcl::PointCloud< PointT > &pc, const Eigen::Vector3d &localmapsize, unsigned int maxnumpoints=1e9, float occupancy_limit=255, double maxz=100.0, double sensor_noise=0.25) |
void | addPointCloudSimple (const pcl::PointCloud< PointT > &pc, double maxz=100.0) |
virtual void | computeNDTCells (int cellupdatemode=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) |
void | computeNDTCellsSimple () |
void | debugToVRML (const char *fname, pcl::PointCloud< PointT > &pc) |
virtual std::vector < lslgeneric::NDTCell< PointT > * > | getAllCells () const |
virtual std::vector < lslgeneric::NDTCell< PointT > * > | getAllInitializedCells () |
virtual bool | getCellAtPoint (const PointT &refPoint, NDTCell< PointT > *&cell) |
Get the cell for which the point fall into (not the closest cell) | |
virtual bool | getCellForPoint (const PointT &refPoint, NDTCell< PointT > *&cell, bool checkForGaussian=true) const |
NDTCell< PointT > * | getCellIdx (unsigned int idx) const |
return the cell using a specific index (not available for all spatialindexes), will return NULL if the idx is not valid. | |
virtual std::vector< NDTCell < PointT > * > | getCellsForPoint (const PointT pt, int n_neighbours, bool checkForGaussian=true) const |
virtual bool | getCentroid (double &cx, double &cy, double &cz) |
double | getDepth (Eigen::Vector3d origin, Eigen::Vector3d dir, double maxDepth=100) |
double | getDepthSmooth (Eigen::Vector3d origin, Eigen::Vector3d dir, double maxDepth=20, int n_neigh=1, double weight=5.0, double threshold=0.2, Eigen::Vector3d *hit=NULL) |
bool | getGridSizeInMeters (double &cx, double &cy, double &cz) |
virtual std::vector< NDTCell < PointT > * > | getInitializedCellsForPoint (const PointT pt) const |
virtual double | getLikelihoodForPoint (PointT pt) |
SpatialIndex< PointT > * | getMyIndex () const |
int | getMyIndexInt () const |
return the spatial index used as an integer | |
std::string | getMyIndexStr () const |
return the spatial index used as a string | |
void | guessSize (float cenx, float ceny, float cenz, float sizex, float sizey, float sizez) |
void | initialize (double cenx, double ceny, double cenz, double sizex, double sizey, double sizez) |
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) |
int | loadFromJFF (const char *filename) |
virtual void | loadPointCloud (const pcl::PointCloud< PointT > &pc, double range_limit=-1) |
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. | |
void | loadPointCloudCentroid (const pcl::PointCloud< PointT > &pc, const Eigen::Vector3d &origin, const Eigen::Vector3d &old_centroid, const Eigen::Vector3d &map_size, double range_limit) |
NDTMap () | |
NDTMap (SpatialIndex< PointT > *idx) | |
NDTMap (const NDTMap &other) | |
NDTMap (SpatialIndex< PointT > *idx, float cenx, float ceny, float cenz, float sizex, float sizey, float sizez) | |
int | numberOfActiveCells () |
virtual std::vector< NDTCell < PointT > * > | pseudoTransformNDT (Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > T) |
NDTMap< PointT > * | pseudoTransformNDTMap (Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > T) |
void | setMapSize (float sx, float sy, float sz) |
void | setMode (bool is3D_) |
int | writeCellVectorJFF (FILE *jffout) |
int | writeLazyGridJFF (FILE *jffout) |
int | writeOctTreeJFF (FILE *jffout) |
int | writeToJFF (const char *filename) |
void | writeToVRML (const char *filename) |
virtual void | writeToVRML (FILE *fout) |
virtual void | writeToVRML (FILE *fout, Eigen::Vector3d col) |
virtual | ~NDTMap () |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW pcl::PointCloud< PointT > | conflictPoints |
points that were conflicting during update | |
Protected Attributes | |
float | centerx |
float | centery |
float | centerz |
bool | guess_size_ |
SpatialIndex< PointT > * | index_ |
bool | is3D |
bool | isFirstLoad_ |
float | map_sizex |
float | map_sizey |
float | map_sizez |
std::set< NDTCell< PointT > * > | update_set |
Implements an NDT based spatial index.
This class contains an interface to a SpatialIndex (custom defined) that contains NDT cells. Provides methods to create from a PointCloud.
This class implements two approaches to NDT mapping - "traditional" NDT approach, as well as a novel NDT Occupancy Map approach.
The "traditional" approach uses only the measurement points and a single scan in order to construct the NDT map.
The NDT-OM fuses incrementally measurement using Recursive Sample Covariance (RSC) approach. It also models the occupancy and free space, it adapts to changes in the cell etc.
Having these two versions combined also means that not all features are working with both. The known NDT-OM issues are
The old interface (e.g. used in registration) loadPointCloud(const pcl::PointCloud<PointT> &pc, double range_limit = -1); works as before: it computes an NDT map using only the samples and without tracking occupancy.
Since version 2.0 the ndt_map integrates also incremental update features. These are accessible through two methods: 1) void addPointCloudSimple(const pcl::PointCloud<PointT> &pc,double maxz=100.0); 2) void addPointCloud(const Eigen::Vector3d &origin, const pcl::PointCloud<PointT> &pc, double classifierTh=0.06, double maxz = 100.0, double sensor_noise = 0.25);
The first one only updates the measurement points and thus is faster, but does not model free space and does not tolerate dynamics The second one uses ray tracing and a number of approaches to model the occupancy as well as adapts to the dynamics.
In all cases the procedure to use the ndt_map is the following: 1) Add the measurement (by above mentioned load or add methods) 2) call computeNDTCells
Afer this the map is updated. There are various methods to access the map elements documented in this header file that you may use.
This class implements now the following papers, which you hopefully cite if you find this useful: Normal Distributions Transform Occupancy Maps: Application to Large-Scale Online 3D Mapping. IEEE International Conference on Robotics and Automation (ICRA 2013), 2013. There is also an implementation of modeling of the dynamics (edata structure in ndt_cell): "Independent Markov chain occupancy grid maps for representation of dynamic environments," in IROS2012 Conference Proceedings, Vilamoura, Algarve, Portugal: IEEE, 2012, pp. 3489-3495.
In addition, this class provide the basis for NDT registration, which is further discussed in the ndt_registration package. The relevant publications are:
lslgeneric::NDTMap< PointT >::NDTMap | ( | ) | [inline] |
lslgeneric::NDTMap< PointT >::NDTMap | ( | SpatialIndex< PointT > * | idx | ) | [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
lslgeneric::NDTMap< PointT >::NDTMap | ( | const NDTMap< PointT > & | other | ) | [inline] |
lslgeneric::NDTMap< PointT >::NDTMap | ( | SpatialIndex< PointT > * | idx, |
float | cenx, | ||
float | ceny, | ||
float | cenz, | ||
float | sizex, | ||
float | sizey, | ||
float | sizez | ||
) | [inline] |
virtual lslgeneric::NDTMap< PointT >::~NDTMap | ( | ) | [inline, virtual] |
void lslgeneric::NDTMap< PointT >::addDistributionToCell | ( | const Eigen::Matrix3d & | ucov, |
const Eigen::Vector3d & | umean, | ||
unsigned int | numpointsindistribution, | ||
float | r = 0 , |
||
float | g = 0 , |
||
float | b = 0 , |
||
unsigned int | maxnumpoints = 1e9 , |
||
float | max_occupancy = 1024 |
||
) |
Adds a sample mean and covariance to the map
&ucov | The covariance matrix to be added |
&umean | The mean of the normal distribution |
numpointsindistribution | The number of points used in computation of the sample mean and covariance |
r,g,b | -- optional color parameters |
maxnumpoints | -- optional adaptation of the gaussians |
Add a distribution to the map
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
Definition at line 327 of file ndt_map.hpp.
bool lslgeneric::NDTMap< PointT >::addMeasurement | ( | const Eigen::Vector3d & | origin, |
PointT | endpoint, | ||
double | classifierTh, | ||
double | maxz, | ||
double | sensor_noise | ||
) | [virtual] |
Adds one measurement to the map using NDT-OM update step
Select the smallest resolution
We only want to check every cell once, so increase the index if we are still in the same cell
Check the validity of the index
< endpoint
< don't accept points further than the measurement
<distance to endpoint
test for distance based sensor noise
This is the probability of max lik point being endpoint
Evidence value for empty - alpha * p(x);
The cell does not have gaussian, so we mark that we saw it empty...
Add fake point to initialize!
Definition at line 896 of file ndt_map.hpp.
void lslgeneric::NDTMap< PointT >::addPointCloud | ( | const Eigen::Vector3d & | origin, |
const pcl::PointCloud< PointT > & | pc, | ||
double | classifierTh = 0.06 , |
||
double | maxz = 100.0 , |
||
double | sensor_noise = 0.25 , |
||
double | occupancy_limit = 255 |
||
) | [virtual] |
Add new pointcloud to map - This is the main interface for NDT-OM! Performs raytracing, updates conflicts and adds points to cells computeNDTCells must be called after calling this
&origin | is the position of the sensor, from where the scan has been taken from. |
&pc | is the pointcloud to be added |
classifierTh | A treshold to judge if the ray passes through a gaussian (obsolete) |
maxz | threshold for the maximum z-coordinate value for the measurement point_cloud |
sensor_noise | The expected standard deviation of the sensor noise |
Adds a new cloud: NDT-OM update step
Select the smallest resolution
We only want to check every cell once, so increase the index if we are still in the same cell
Check the validity of the index
< don't accept points further than the measurement
<distance to endpoint
test for distance based sensor noise
This is the probability of max lik point being endpoint
Evidence value for empty - alpha * p(x);
The cell does not have gaussian, so we mark that we saw it empty...
Add fake point to initialize!
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
Definition at line 436 of file ndt_map.hpp.
void lslgeneric::NDTMap< PointT >::addPointCloudMeanUpdate | ( | const Eigen::Vector3d & | origin, |
const pcl::PointCloud< PointT > & | pc, | ||
const Eigen::Vector3d & | localmapsize, | ||
unsigned int | maxnumpoints = 1e9 , |
||
float | occupancy_limit = 255 , |
||
double | maxz = 100.0 , |
||
double | sensor_noise = 0.25 |
||
) | [virtual] |
Add new pointcloud to map - Updates the occupancy using the mean values of a local map generated from an observation
Performs raytracing, updates conflicts and adds points to cells computeNDTCells must be called after calling this
&origin | is the position of the sensor, from where the scan has been taken from. |
&pc | is the pointcloud to be added |
&localmapsize | The dimensions of the local map used for computing the gaussians |
maxnumpoints | Defines the forgetting factor (default 100000) the smaller the value the faster the adaptation |
occupancy_limit | Clamping threshold for log-odds value |
maxz | threshold for the maximum z-coordinate value for the measurement point_cloud |
sensor_noise | The expected standard deviation of the sensor noise |
fprintf(stderr,"UPDATING\n");
Select the smallest resolution
Lets first create a local ndmap (this really works only if we have lazy grid as well)
FIXME:: fixed max length
Use Student-T
Use Sample variance
TODO: This returns now copies --- should be pointers?
Lets update negative even though the measurement was too high
We only want to check every cell once, so increase the index if we are still in the same cell
Check the validity of the index
< don't accept points further than the measurement
<distance to endpoint
test for distance based sensor noise
This is the probability of max lik point being endpoint
Evidence value for empty - alpha * p(x);
The cell does not have gaussian, so we mark that we saw it empty...
Add fake point to initialize!
<FIXME:: local implementation can be faster?
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
Definition at line 694 of file ndt_map.hpp.
void lslgeneric::NDTMap< PointT >::addPointCloudSimple | ( | const pcl::PointCloud< PointT > & | pc, |
double | maxz = 100.0 |
||
) |
This interface updates only the end points into the map without raytracing
Just adds the points, without raytracing and such
Definition at line 283 of file ndt_map.hpp.
void lslgeneric::NDTMap< PointT >::computeNDTCells | ( | int | cellupdatemode = 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 |
||
) | [virtual] |
Computes the NDT-cells after a measurement has been added
cellupdatemode | Defines the update mode (default CELL_UPDATE_MODE_SAMPLE_VARIANCE) |
maxnumpoints | Defines the forgetting factor (default 100000) the smaller the value the faster the adaptation |
Helper function, computes the NDTCells
Process the conflict points
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
Definition at line 1298 of file ndt_map.hpp.
void lslgeneric::NDTMap< PointT >::computeNDTCellsSimple | ( | ) |
Computes the Normaldistribution parameters without erasing the points
Computes the normaldistribution parameters and leaves the points a
Definition at line 1398 of file ndt_map.hpp.
void lslgeneric::NDTMap< PointT >::debugToVRML | ( | const char * | fname, |
pcl::PointCloud< PointT > & | pc | ||
) |
Definition at line 2094 of file ndt_map.hpp.
std::vector< lslgeneric::NDTCell< PointT > * > lslgeneric::NDTMap< PointT >::getAllCells | ( | ) | const [virtual] |
Returns all computed cells from the map This method gives all the vectors that contain a gaussian within a cell (hasGaussian is true).
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
Definition at line 2218 of file ndt_map.hpp.
std::vector< lslgeneric::NDTCell< PointT > * > lslgeneric::NDTMap< PointT >::getAllInitializedCells | ( | ) | [virtual] |
Returns all cells that have been initialized (including ones that do not contain gaussian at the moment). This is useful if you want to use the empty cells or dynamic cells
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
Definition at line 2243 of file ndt_map.hpp.
bool lslgeneric::NDTMap< PointT >::getCellAtPoint | ( | const PointT & | refPoint, |
NDTCell< PointT > *& | cell | ||
) | [virtual] |
Get the cell for which the point fall into (not the closest cell)
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
Definition at line 388 of file ndt_map.hpp.
bool lslgeneric::NDTMap< PointT >::getCellForPoint | ( | const PointT & | refPoint, |
NDTCell< PointT > *& | cell, | ||
bool | checkForGaussian = true |
||
) | const [virtual] |
returns the closest cell to refPoint Does not work with NDT-OM
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
Definition at line 2067 of file ndt_map.hpp.
NDTCell< PointT > * lslgeneric::NDTMap< PointT >::getCellIdx | ( | unsigned int | idx | ) | const |
return the cell using a specific index (not available for all spatialindexes), will return NULL if the idx is not valid.
Definition at line 2207 of file ndt_map.hpp.
std::vector< NDTCell< PointT > * > lslgeneric::NDTMap< PointT >::getCellsForPoint | ( | const PointT | pt, |
int | n_neighbours, | ||
bool | checkForGaussian = true |
||
) | const [virtual] |
Returns all the cells within radius Does not work with NDT-OM
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
Definition at line 2048 of file ndt_map.hpp.
virtual bool lslgeneric::NDTMap< PointT >::getCentroid | ( | double & | cx, |
double & | cy, | ||
double & | cz | ||
) | [inline, virtual] |
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
double lslgeneric::NDTMap< PointT >::getDepth | ( | Eigen::Vector3d | origin, |
Eigen::Vector3d | dir, | ||
double | maxDepth = 100 |
||
) |
Computes a maximum likelihood depth from the map, given a position and a view vector
Get estimated depth This goes through now the cells always to max depth and is not the most efficient solution
Definition at line 1051 of file ndt_map.hpp.
double lslgeneric::NDTMap< PointT >::getDepthSmooth | ( | Eigen::Vector3d | origin, |
Eigen::Vector3d | dir, | ||
double | maxDepth = 20 , |
||
int | n_neigh = 1 , |
||
double | weight = 5.0 , |
||
double | threshold = 0.2 , |
||
Eigen::Vector3d * | hit = NULL |
||
) |
Definition at line 1097 of file ndt_map.hpp.
bool lslgeneric::NDTMap< PointT >::getGridSizeInMeters | ( | double & | cx, |
double & | cy, | ||
double & | cz | ||
) | [inline] |
std::vector< NDTCell< PointT > * > lslgeneric::NDTMap< PointT >::getInitializedCellsForPoint | ( | const PointT | pt | ) | const [virtual] |
Returns all the cells within radius
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
Definition at line 2033 of file ndt_map.hpp.
double lslgeneric::NDTMap< PointT >::getLikelihoodForPoint | ( | PointT | pt | ) | [virtual] |
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
Definition at line 1836 of file ndt_map.hpp.
SpatialIndex<PointT>* lslgeneric::NDTMap< PointT >::getMyIndex | ( | ) | const [inline] |
int lslgeneric::NDTMap< PointT >::getMyIndexInt | ( | ) | const |
return the spatial index used as an integer
returns the current spatial index as an integer (debugging function)
Definition at line 1813 of file ndt_map.hpp.
std::string lslgeneric::NDTMap< PointT >::getMyIndexStr | ( | ) | const |
return the spatial index used as a string
returns the current spatial index as a string (debugging function)
Definition at line 1790 of file ndt_map.hpp.
void lslgeneric::NDTMap< PointT >::guessSize | ( | float | cenx, |
float | ceny, | ||
float | cenz, | ||
float | sizex, | ||
float | sizey, | ||
float | sizez | ||
) | [inline] |
void lslgeneric::NDTMap< PointT >::initialize | ( | double | cenx, |
double | ceny, | ||
double | cenz, | ||
double | sizex, | ||
double | sizey, | ||
double | sizez | ||
) | [inline] |
void lslgeneric::NDTMap< PointT >::loadDepthImage | ( | const cv::Mat & | depthImage, |
DepthCamera< PointT > & | cameraParams | ||
) |
Definition at line 1192 of file ndt_map.hpp.
pcl::PointCloud< PointT > lslgeneric::NDTMap< 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 1200 of file ndt_map.hpp.
int lslgeneric::NDTMap< PointT >::loadFromJFF | ( | const char * | filename | ) |
method to load NDT maps from .jff files USAGE: create NDTMap with desired index and PointType (index type is checked, but Point type is NOT checked) via e.g.
lslgeneric::NDTMap<pcl::PointXYZ> nd1( new lslgeneric::LazyGrid<pcl::PointXYZ>(0.4)); --> (*)
and then call
nd1.loadFromJFF("map0027.jff");
) use this constructor so index is not initialized and attributes can be set manually
Definition at line 1696 of file ndt_map.hpp.
void lslgeneric::NDTMap< PointT >::loadPointCloud | ( | const pcl::PointCloud< PointT > & | pc, |
double | range_limit = -1 |
||
) | [virtual] |
loadPointCloud - You can call this if you are only interested in dealing with one scan without need for fusing several ones or representing empty space and occupancy
Otherwise you should always call addPointCloud (or if you don't want occupancy then addPointCloudSimple)
pc | the PointCloud that is to be loaded |
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
Definition at line 31 of file ndt_map.hpp.
void lslgeneric::NDTMap< 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.
NOTE: These load functions are not supported by occupancy mapping This function loads a point cloud around specific indeces for usage in NFT-feature based mapping.
&pc | the Point Cloud to use as input |
&indices | a vector of the indeces that will be added for each cell. We add indices.size() number of cells, each cell c[i] contains the points, indexed by the vector indices[i] |
Definition at line 1171 of file ndt_map.hpp.
void lslgeneric::NDTMap< PointT >::loadPointCloudCentroid | ( | const pcl::PointCloud< PointT > & | pc, |
const Eigen::Vector3d & | origin, | ||
const Eigen::Vector3d & | old_centroid, | ||
const Eigen::Vector3d & | map_size, | ||
double | range_limit | ||
) |
loadPointCloudCentroid - A special load function to enable the matching of centroids (create alligned maps) This is more efficient than the standard, but needs also the origin and size as parameters
&pc | the PointCloud that is to be loaded |
&origin | The desired origin of the map (will be fitted acording to old_centroid) |
&old_centroid | The centroid to which we want to align |
&map_size | The size of the new map |
range_limit | The maximum range value for measurements |
loadPointCloudCentroid - A special load function to enable the matching of centroids (create alligned maps)
pc | the PointCloud that is to be loaded |
Should never happen!
How many cell to each direction is the new origin from old one
Definition at line 197 of file ndt_map.hpp.
int lslgeneric::NDTMap< PointT >::numberOfActiveCells | ( | ) |
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
Definition at line 2267 of file ndt_map.hpp.
std::vector< NDTCell< PointT > * > lslgeneric::NDTMap< PointT >::pseudoTransformNDT | ( | Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > | T | ) | [virtual] |
Returns a transformed NDT as a vector of NDT cells
NOTE: The rotation of the covariance fixed by Jari 6.11.2012
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
Definition at line 2173 of file ndt_map.hpp.
NDTMap< PointT > * lslgeneric::NDTMap< PointT >::pseudoTransformNDTMap | ( | Eigen::Transform< double, 3, Eigen::Affine, Eigen::ColMajor > | T | ) |
Returns a transformed NDT as an NDT map with a CellVector data structure
NOTE: The rotation of the covariance fixed by Jari 6.11.2012
Definition at line 2139 of file ndt_map.hpp.
void lslgeneric::NDTMap< PointT >::setMapSize | ( | float | sx, |
float | sy, | ||
float | sz | ||
) | [inline] |
void lslgeneric::NDTMap< PointT >::setMode | ( | bool | is3D_ | ) | [inline] |
int lslgeneric::NDTMap< PointT >::writeCellVectorJFF | ( | FILE * | jffout | ) |
Definition at line 1570 of file ndt_map.hpp.
int lslgeneric::NDTMap< PointT >::writeLazyGridJFF | ( | FILE * | jffout | ) |
Definition at line 1635 of file ndt_map.hpp.
int lslgeneric::NDTMap< PointT >::writeOctTreeJFF | ( | FILE * | jffout | ) |
Definition at line 1603 of file ndt_map.hpp.
int lslgeneric::NDTMap< PointT >::writeToJFF | ( | const char * | filename | ) |
output methods for saving the map in the jff format
Definition at line 1534 of file ndt_map.hpp.
void lslgeneric::NDTMap< PointT >::writeToVRML | ( | const char * | filename | ) |
Stuff for saving things
output method, saves as vrml the oct tree and all the ellipsoids
Definition at line 1442 of file ndt_map.hpp.
void lslgeneric::NDTMap< PointT >::writeToVRML | ( | FILE * | fout | ) | [virtual] |
helper output method
Definition at line 1478 of file ndt_map.hpp.
void lslgeneric::NDTMap< PointT >::writeToVRML | ( | FILE * | fout, |
Eigen::Vector3d | col | ||
) | [virtual] |
Definition at line 1506 of file ndt_map.hpp.
float lslgeneric::NDTMap< PointT >::centerx [protected] |
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
float lslgeneric::NDTMap< PointT >::centery [protected] |
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
float lslgeneric::NDTMap< PointT >::centerz [protected] |
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW pcl::PointCloud<PointT> lslgeneric::NDTMap< PointT >::conflictPoints |
points that were conflicting during update
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
bool lslgeneric::NDTMap< PointT >::guess_size_ [protected] |
SpatialIndex<PointT>* lslgeneric::NDTMap< PointT >::index_ [protected] |
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
bool lslgeneric::NDTMap< PointT >::is3D [protected] |
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
bool lslgeneric::NDTMap< PointT >::isFirstLoad_ [protected] |
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
float lslgeneric::NDTMap< PointT >::map_sizex [protected] |
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
float lslgeneric::NDTMap< PointT >::map_sizey [protected] |
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
float lslgeneric::NDTMap< PointT >::map_sizez [protected] |
Reimplemented in lslgeneric::NDTMapHMT< PointT >.
std::set<NDTCell<PointT>*> lslgeneric::NDTMap< PointT >::update_set [protected] |
Reimplemented in lslgeneric::NDTMapHMT< PointT >.