|
Point Cloud Library (PCL)
1.15.1-dev
|
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< PointType > | fetchCloud (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... | |
TsdfVolume class.
Definition at line 62 of file tsdf_volume.h.
| using pcl::gpu::kinfuLS::TsdfVolume::ConstPtr = shared_ptr<const TsdfVolume> |
Definition at line 66 of file tsdf_volume.h.
Definition at line 70 of file tsdf_volume.h.
Supported Point Types.
Definition at line 69 of file tsdf_volume.h.
| using pcl::gpu::kinfuLS::TsdfVolume::Ptr = shared_ptr<TsdfVolume> |
Definition at line 65 of file tsdf_volume.h.
| 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.
| pcl::gpu::kinfuLS::TsdfVolume::TsdfVolume | ( | const Eigen::Vector3i & | resolution | ) |
Constructor.
| [in] | resolution | volume resolution |
| 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.
| [out] | cloud | - the output point cloud |
| [in] | step | - the decimation step to use |
| DeviceArray2D<int> pcl::gpu::kinfuLS::TsdfVolume::data | ( | ) | const |
Returns tsdf volume container that point to data in GPU memory.
| void pcl::gpu::kinfuLS::TsdfVolume::downloadTsdf | ( | std::vector< float > & | tsdf | ) | const |
Downloads tsdf volume from GPU memory.
| [out] | tsdf | Array 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]; |
| 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.
| [out] | tsdf | Array 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] | weights | Array with tsdf voxel weights. Same size and access index as for tsdf. A weight of 0 indicates the voxel was never used. |
| void pcl::gpu::kinfuLS::TsdfVolume::downloadTsdfAndWeightsLocal | ( | ) | const |
Downloads TSDF volume and according voxel weights from GPU memory to local CPU buffers.
| void pcl::gpu::kinfuLS::TsdfVolume::downloadTsdfLocal | ( | ) | const |
Downloads tsdf volume from GPU memory to local CPU buffer.
| DeviceArray<PointType> pcl::gpu::kinfuLS::TsdfVolume::fetchCloud | ( | DeviceArray< PointType > & | cloud_buffer | ) | const |
Generates cloud using GPU in connected6 mode only.
| [out] | cloud_buffer | buffer to store point cloud |
| void pcl::gpu::kinfuLS::TsdfVolume::fetchCloudHost | ( | PointCloud< PointType > & | cloud, |
| bool | connected26 = false |
||
| ) | const |
Generates cloud using CPU (downloads volumetric representation to CPU memory)
| [out] | cloud | output array for cloud |
| [in] | connected26 | If false point cloud is extracted using 6 neighbor, otherwise 26. |
| void pcl::gpu::kinfuLS::TsdfVolume::fetchCloudHost | ( | PointCloud< PointXYZI > & | cloud, |
| bool | connected26 = false |
||
| ) | const |
Generates cloud using CPU (downloads volumetric representation to CPU memory)
| [out] | cloud | output array for cloud |
| [in] | connected26 | If false point cloud is extracted using 6 neighbor, otherwise 26. |
| void pcl::gpu::kinfuLS::TsdfVolume::fetchNormals | ( | const DeviceArray< PointType > & | cloud, |
| DeviceArray< NormalType > & | normals | ||
| ) | const |
Computes normals as gradient of tsdf for given points.
| [in] | cloud | Points where normals are computed. |
| [out] | normals | array for normals |
| void pcl::gpu::kinfuLS::TsdfVolume::fetchNormals | ( | const DeviceArray< PointType > & | cloud, |
| DeviceArray< PointType > & | normals | ||
| ) | const |
Computes normals as gradient of tsdf for given points.
| [in] | cloud | Points where normals are computed. |
| [out] | normals | array for normals |
| 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.
| [out] | cloud_buffer_xyz | buffer to store point cloud |
| cloud_buffer_intensity | ||
| [in] | buffer | Pointer to the buffer struct that contains information about memory addresses of the tsdf volume memory block, which are used for the cyclic buffer. |
| [in] | shiftX | Offset in indices. |
| [in] | shiftY | Offset in indices. |
| [in] | shiftZ | Offset in indices. |
| const Eigen::Vector3i& pcl::gpu::kinfuLS::TsdfVolume::getResolution | ( | ) | const |
Returns volume resolution.
| const Eigen::Vector3f& pcl::gpu::kinfuLS::TsdfVolume::getSize | ( | ) | const |
Returns volume size in meters.
| float pcl::gpu::kinfuLS::TsdfVolume::getTsdfTruncDist | ( | ) | const |
Returns tsdf truncation distance in meters.
| const Eigen::Vector3f pcl::gpu::kinfuLS::TsdfVolume::getVoxelSize | ( | ) | const |
Returns volume voxel size in meters.
|
inline |
Returns the voxel grid resolution.
Definition at line 257 of file tsdf_volume.h.
| bool pcl::gpu::kinfuLS::TsdfVolume::load | ( | const std::string & | filename, |
| bool | binary = true |
||
| ) |
Loads local volume from file.
| void pcl::gpu::kinfuLS::TsdfVolume::print_warn | ( | const char * | arg1, |
| std::size_t | size | ||
| ) |
| 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.
| [in] | existing_data_cloud | point 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 |
|
inline |
Releases tsdf buffer on GPU.
Definition at line 229 of file tsdf_volume.h.
| void pcl::gpu::kinfuLS::TsdfVolume::reset | ( | ) |
Resets tsdf volume data to uninitialized state.
| bool pcl::gpu::kinfuLS::TsdfVolume::save | ( | const std::string & | filename = "tsdf_volume.dat", |
| bool | binary = true |
||
| ) | const |
Saves local volume buffer to file.
|
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().
| void pcl::gpu::kinfuLS::TsdfVolume::setSize | ( | const Eigen::Vector3f & | size | ) |
Sets Tsdf volume size for each dimension.
| [in] | size | size of tsdf volume in meters |
| void pcl::gpu::kinfuLS::TsdfVolume::setTsdfTruncDist | ( | float | distance | ) |
Sets Tsdf truncation distance.
Must be greater than 2 * volume_voxel_size
| [in] | distance | TSDF truncation distance |
|
inline |
Returns overall number of voxels in grid stored on host.
Definition at line 243 of file tsdf_volume.h.