Point Cloud Library (PCL)  1.14.0-dev
List of all members | Classes | Public Types | Public Member Functions
pcl::gpu::kinfuLS::TsdfVolume Class Reference

TsdfVolume class. More...

#include </__w/1/s/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/tsdf_volume.h>

Classes

struct  Header
 Structure storing voxel grid resolution, volume size (in mm) and element_size of data stored on host. More...
 

Public Types

enum  { DEFAULT_CLOUD_BUFFER_SIZE = 10 * 1000 * 1000 }
 Default buffer size for fetching cloud. More...
 
using Ptr = shared_ptr< TsdfVolume >
 
using ConstPtr = shared_ptr< const TsdfVolume >
 
using PointType = PointXYZ
 Supported Point Types. More...
 
using NormalType = Normal
 

Public Member Functions

 TsdfVolume (const Eigen::Vector3i &resolution)
 Constructor. More...
 
void setSize (const Eigen::Vector3f &size)
 Sets Tsdf volume size for each dimension. More...
 
void setTsdfTruncDist (float distance)
 Sets Tsdf truncation distance. More...
 
DeviceArray2D< int > data () const
 Returns tsdf volume container that point to data in GPU memory. More...
 
const Eigen::Vector3f & getSize () const
 Returns volume size in meters. More...
 
const Eigen::Vector3i & getResolution () const
 Returns volume resolution. More...
 
const Eigen::Vector3f getVoxelSize () const
 Returns volume voxel size in meters. More...
 
float getTsdfTruncDist () const
 Returns tsdf truncation distance in meters. More...
 
void reset ()
 Resets tsdf volume data to uninitialized state. More...
 
void fetchCloudHost (PointCloud< PointType > &cloud, bool connected26=false) const
 Generates cloud using CPU (downloads volumetric representation to CPU memory) More...
 
void fetchCloudHost (PointCloud< PointXYZI > &cloud, bool connected26=false) const
 Generates cloud using CPU (downloads volumetric representation to CPU memory) More...
 
DeviceArray< PointTypefetchCloud (DeviceArray< PointType > &cloud_buffer) const
 Generates cloud using GPU in connected6 mode only. More...
 
void pushSlice (const PointCloud< PointXYZI >::Ptr existing_data_cloud, const tsdf_buffer *buffer) const
 Push a point cloud of previously scanned tsdf slice to the TSDF volume. More...
 
std::size_t fetchSliceAsCloud (DeviceArray< PointType > &cloud_buffer_xyz, DeviceArray< float > &cloud_buffer_intensity, const tsdf_buffer *buffer, int shiftX, int shiftY, int shiftZ) const
 Generates cloud using GPU in connected6 mode only. More...
 
void fetchNormals (const DeviceArray< PointType > &cloud, DeviceArray< PointType > &normals) const
 Computes normals as gradient of tsdf for given points. More...
 
void fetchNormals (const DeviceArray< PointType > &cloud, DeviceArray< NormalType > &normals) const
 Computes normals as gradient of tsdf for given points. More...
 
void downloadTsdf (std::vector< float > &tsdf) const
 Downloads tsdf volume from GPU memory. More...
 
void downloadTsdfLocal () const
 Downloads tsdf volume from GPU memory to local CPU buffer. More...
 
void downloadTsdfAndWeights (std::vector< float > &tsdf, std::vector< short > &weights) const
 Downloads TSDF volume and according voxel weights from GPU memory. More...
 
void downloadTsdfAndWeightsLocal () const
 Downloads TSDF volume and according voxel weights from GPU memory to local CPU buffers. More...
 
void releaseVolume ()
 Releases tsdf buffer on GPU. More...
 
void print_warn (const char *arg1, std::size_t size)
 
void setHeader (const Eigen::Vector3i &resolution, const Eigen::Vector3f &volume_size)
 Set the header for data stored on host directly. More...
 
std::size_t size () const
 Returns overall number of voxels in grid stored on host. More...
 
void convertToTsdfCloud (pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, const unsigned step=2) const
 Converts volume stored on host to cloud of TSDF values. More...
 
const Eigen::Vector3i & gridResolution () const
 Returns the voxel grid resolution. More...
 
bool save (const std::string &filename="tsdf_volume.dat", bool binary=true) const
 Saves local volume buffer to file. More...
 
bool load (const std::string &filename, bool binary=true)
 Loads local volume from file. More...
 

Detailed Description

TsdfVolume class.

Author
Anatoly Baskeheev, Itseez Ltd, (mynam.nosp@m.e.my.nosp@m.surna.nosp@m.me@m.nosp@m.ycomp.nosp@m.any..nosp@m.com)

Definition at line 62 of file tsdf_volume.h.

Member Typedef Documentation

◆ ConstPtr

Definition at line 66 of file tsdf_volume.h.

◆ NormalType

Definition at line 70 of file tsdf_volume.h.

◆ PointType

Supported Point Types.

Definition at line 69 of file tsdf_volume.h.

◆ Ptr

Definition at line 65 of file tsdf_volume.h.

Member Enumeration Documentation

◆ anonymous enum

anonymous enum

Default buffer size for fetching cloud.

It limits max number of points that can be extracted

Enumerator
DEFAULT_CLOUD_BUFFER_SIZE 

Definition at line 109 of file tsdf_volume.h.

Constructor & Destructor Documentation

◆ TsdfVolume()

pcl::gpu::kinfuLS::TsdfVolume::TsdfVolume ( const Eigen::Vector3i &  resolution)

Constructor.

Parameters
[in]resolutionvolume resolution

Member Function Documentation

◆ convertToTsdfCloud()

void pcl::gpu::kinfuLS::TsdfVolume::convertToTsdfCloud ( pcl::PointCloud< pcl::PointXYZI >::Ptr cloud,
const unsigned  step = 2 
) const

Converts volume stored on host to cloud of TSDF values.

Parameters
[out]cloud- the output point cloud
[in]step- the decimation step to use

◆ data()

DeviceArray2D<int> pcl::gpu::kinfuLS::TsdfVolume::data ( ) const

Returns tsdf volume container that point to data in GPU memory.

◆ downloadTsdf()

void pcl::gpu::kinfuLS::TsdfVolume::downloadTsdf ( std::vector< float > &  tsdf) const

Downloads tsdf volume from GPU memory.

Parameters
[out]tsdfArray with tsdf values. if volume resolution is 512x512x512, so for voxel (x,y,z) tsdf value can be retrieved as volume[512*512*z + 512*y + x];

◆ downloadTsdfAndWeights()

void pcl::gpu::kinfuLS::TsdfVolume::downloadTsdfAndWeights ( std::vector< float > &  tsdf,
std::vector< short > &  weights 
) const

Downloads TSDF volume and according voxel weights from GPU memory.

Parameters
[out]tsdfArray with tsdf values. if volume resolution is 512x512x512, so for voxel (x,y,z) tsdf value can be retrieved as volume[512*512*z + 512*y + x];
[out]weightsArray with tsdf voxel weights. Same size and access index as for tsdf. A weight of 0 indicates the voxel was never used.

◆ downloadTsdfAndWeightsLocal()

void pcl::gpu::kinfuLS::TsdfVolume::downloadTsdfAndWeightsLocal ( ) const

Downloads TSDF volume and according voxel weights from GPU memory to local CPU buffers.

◆ downloadTsdfLocal()

void pcl::gpu::kinfuLS::TsdfVolume::downloadTsdfLocal ( ) const

Downloads tsdf volume from GPU memory to local CPU buffer.

◆ fetchCloud()

DeviceArray<PointType> pcl::gpu::kinfuLS::TsdfVolume::fetchCloud ( DeviceArray< PointType > &  cloud_buffer) const

Generates cloud using GPU in connected6 mode only.

Parameters
[out]cloud_bufferbuffer to store point cloud
Returns
DeviceArray with disabled reference counting that points to filled part of cloud_buffer.

◆ fetchCloudHost() [1/2]

void pcl::gpu::kinfuLS::TsdfVolume::fetchCloudHost ( PointCloud< PointType > &  cloud,
bool  connected26 = false 
) const

Generates cloud using CPU (downloads volumetric representation to CPU memory)

Parameters
[out]cloudoutput array for cloud
[in]connected26If false point cloud is extracted using 6 neighbor, otherwise 26.

◆ fetchCloudHost() [2/2]

void pcl::gpu::kinfuLS::TsdfVolume::fetchCloudHost ( PointCloud< PointXYZI > &  cloud,
bool  connected26 = false 
) const

Generates cloud using CPU (downloads volumetric representation to CPU memory)

Parameters
[out]cloudoutput array for cloud
[in]connected26If false point cloud is extracted using 6 neighbor, otherwise 26.

◆ fetchNormals() [1/2]

void pcl::gpu::kinfuLS::TsdfVolume::fetchNormals ( const DeviceArray< PointType > &  cloud,
DeviceArray< NormalType > &  normals 
) const

Computes normals as gradient of tsdf for given points.

Parameters
[in]cloudPoints where normals are computed.
[out]normalsarray for normals

◆ fetchNormals() [2/2]

void pcl::gpu::kinfuLS::TsdfVolume::fetchNormals ( const DeviceArray< PointType > &  cloud,
DeviceArray< PointType > &  normals 
) const

Computes normals as gradient of tsdf for given points.

Parameters
[in]cloudPoints where normals are computed.
[out]normalsarray for normals

◆ fetchSliceAsCloud()

std::size_t pcl::gpu::kinfuLS::TsdfVolume::fetchSliceAsCloud ( DeviceArray< PointType > &  cloud_buffer_xyz,
DeviceArray< float > &  cloud_buffer_intensity,
const tsdf_buffer buffer,
int  shiftX,
int  shiftY,
int  shiftZ 
) const

Generates cloud using GPU in connected6 mode only.

Parameters
[out]cloud_buffer_xyzbuffer to store point cloud
cloud_buffer_intensity
[in]bufferPointer to the buffer struct that contains information about memory addresses of the tsdf volume memory block, which are used for the cyclic buffer.
[in]shiftXOffset in indices.
[in]shiftYOffset in indices.
[in]shiftZOffset in indices.
Returns
DeviceArray with disabled reference counting that points to filled part of cloud_buffer.

◆ getResolution()

const Eigen::Vector3i& pcl::gpu::kinfuLS::TsdfVolume::getResolution ( ) const

Returns volume resolution.

◆ getSize()

const Eigen::Vector3f& pcl::gpu::kinfuLS::TsdfVolume::getSize ( ) const

Returns volume size in meters.

◆ getTsdfTruncDist()

float pcl::gpu::kinfuLS::TsdfVolume::getTsdfTruncDist ( ) const

Returns tsdf truncation distance in meters.

◆ getVoxelSize()

const Eigen::Vector3f pcl::gpu::kinfuLS::TsdfVolume::getVoxelSize ( ) const

Returns volume voxel size in meters.

◆ gridResolution()

const Eigen::Vector3i& pcl::gpu::kinfuLS::TsdfVolume::gridResolution ( ) const
inline

Returns the voxel grid resolution.

Definition at line 257 of file tsdf_volume.h.

◆ load()

bool pcl::gpu::kinfuLS::TsdfVolume::load ( const std::string &  filename,
bool  binary = true 
)

Loads local volume from file.

◆ print_warn()

void pcl::gpu::kinfuLS::TsdfVolume::print_warn ( const char *  arg1,
std::size_t  size 
)

◆ pushSlice()

void pcl::gpu::kinfuLS::TsdfVolume::pushSlice ( const PointCloud< PointXYZI >::Ptr  existing_data_cloud,
const tsdf_buffer buffer 
) const

Push a point cloud of previously scanned tsdf slice to the TSDF volume.

Parameters
[in]existing_data_cloudpoint cloud pointer to the existing data. This data will be pushed to the TSDf volume. The points with indices outside the range [0 ... VOLUME_X - 1][0 ... VOLUME_Y - 1][0 ... VOLUME_Z - 1] will not be added.
buffer

◆ releaseVolume()

void pcl::gpu::kinfuLS::TsdfVolume::releaseVolume ( )
inline

Releases tsdf buffer on GPU.

Definition at line 229 of file tsdf_volume.h.

◆ reset()

void pcl::gpu::kinfuLS::TsdfVolume::reset ( )

Resets tsdf volume data to uninitialized state.

◆ save()

bool pcl::gpu::kinfuLS::TsdfVolume::save ( const std::string &  filename = "tsdf_volume.dat",
bool  binary = true 
) const

Saves local volume buffer to file.

◆ setHeader()

void pcl::gpu::kinfuLS::TsdfVolume::setHeader ( const Eigen::Vector3i &  resolution,
const Eigen::Vector3f &  volume_size 
)
inline

Set the header for data stored on host directly.

Useful if directly writing into volume and weights

Definition at line 235 of file tsdf_volume.h.

References pcl::console::print_warn().

◆ setSize()

void pcl::gpu::kinfuLS::TsdfVolume::setSize ( const Eigen::Vector3f &  size)

Sets Tsdf volume size for each dimension.

Parameters
[in]sizesize of tsdf volume in meters

◆ setTsdfTruncDist()

void pcl::gpu::kinfuLS::TsdfVolume::setTsdfTruncDist ( float  distance)

Sets Tsdf truncation distance.

Must be greater than 2 * volume_voxel_size

Parameters
[in]distanceTSDF truncation distance

◆ size()

std::size_t pcl::gpu::kinfuLS::TsdfVolume::size ( ) const
inline

Returns overall number of voxels in grid stored on host.

Definition at line 243 of file tsdf_volume.h.


The documentation for this class was generated from the following file: