Classes | Public Member Functions | Private Attributes | List of all members
kfusion::cuda::TsdfVolume Class Reference

#include <tsdf_volume.hpp>

Classes

struct  Entry
 

Public Member Functions

virtual void applyAffine (const Affine3f &affine)
 
virtual void clear ()
 
void clearSlice (const kfusion::tsdf_buffer *buffer, const Vec3i offset) const
 
void create (const Vec3i &dims)
 
CudaData data ()
 
const CudaData data () const
 
DeviceArray< PointfetchCloud (DeviceArray< Point > &cloud_buffer, const tsdf_buffer &buffer) const
 
void fetchNormals (const DeviceArray< Point > &cloud, const tsdf_buffer &buffer, DeviceArray< Normal > &normals) const
 
DeviceArray< PointfetchSliceAsCloud (DeviceArray< Point > &cloud_buffer, const kfusion::tsdf_buffer *buffer, const Vec3i minBounds, const Vec3i maxBounds, const Vec3i globalShift) const
 Generates cloud using GPU in connected6 mode only. More...
 
ushort2 * getCoord (int x, int y, int z, int dim_x, int dim_y)
 
Vec3i getDims () const
 
float getGradientDeltaFactor () const
 
Vec3i getGridOrigin () const
 
int getMaxWeight () const
 
Affine3f getPose () const
 
float getRaycastStepFactor () const
 
Vec3f getSize () const
 
float getTruncDist () const
 
Vec3f getVoxelSize () const
 
virtual void integrate (const Dists &dists, tsdf_buffer &buffer, const Affine3f &camera_pose, const Intr &intr)
 
virtual void raycast (const Affine3f &camera_pose, tsdf_buffer &buffer, const Intr &intr, Cloud &points, Normals &normals)
 
virtual void raycast (const Affine3f &camera_pose, tsdf_buffer &buffer, const Intr &intr, Depth &depth, Normals &normals)
 
void setGradientDeltaFactor (float factor)
 
void setGridOrigin (const Vec3i &origin)
 
void setMaxWeight (int weight)
 
void setPose (const Affine3f &pose)
 
void setRaycastStepFactor (float factor)
 
void setSize (const Vec3f &size)
 
void setTruncDist (float distance)
 
void swap (CudaData &data)
 
 TsdfVolume (const cv::Vec3i &dims)
 TsdfVolume. More...
 
virtual ~TsdfVolume ()
 

Private Attributes

CudaData data_
 
Vec3i dims_
 
float gradient_delta_factor_
 
int max_weight_
 
Affine3f pose_
 
float raycast_step_factor_
 
Vec3f size_
 
float trunc_dist_
 

Detailed Description

Definition at line 11 of file tsdf_volume.hpp.

Constructor & Destructor Documentation

◆ TsdfVolume()

kfusion::cuda::TsdfVolume::TsdfVolume ( const cv::Vec3i &  dims)

TsdfVolume.

Definition at line 18 of file tsdf_volume.cpp.

◆ ~TsdfVolume()

kfusion::cuda::TsdfVolume::~TsdfVolume ( )
virtual

Definition at line 22 of file tsdf_volume.cpp.

Member Function Documentation

◆ applyAffine()

void kfusion::cuda::TsdfVolume::applyAffine ( const Affine3f affine)
virtual

Definition at line 71 of file tsdf_volume.cpp.

◆ clear()

void kfusion::cuda::TsdfVolume::clear ( )
virtual

Definition at line 73 of file tsdf_volume.cpp.

◆ clearSlice()

void kfusion::cuda::TsdfVolume::clearSlice ( const kfusion::tsdf_buffer buffer,
const Vec3i  offset 
) const

Definition at line 82 of file tsdf_volume.cpp.

◆ create()

void kfusion::cuda::TsdfVolume::create ( const Vec3i dims)

Definition at line 24 of file tsdf_volume.cpp.

◆ data() [1/2]

CudaData kfusion::cuda::TsdfVolume::data ( )

◆ data() [2/2]

CudaData kfusion::cuda::TsdfVolume::data ( ) const

Definition at line 41 of file tsdf_volume.cpp.

◆ fetchCloud()

DeviceArray< Point > kfusion::cuda::TsdfVolume::fetchCloud ( DeviceArray< Point > &  cloud_buffer,
const tsdf_buffer buffer 
) const

Definition at line 148 of file tsdf_volume.cpp.

◆ fetchNormals()

void kfusion::cuda::TsdfVolume::fetchNormals ( const DeviceArray< Point > &  cloud,
const tsdf_buffer buffer,
DeviceArray< Normal > &  normals 
) const

Definition at line 167 of file tsdf_volume.cpp.

◆ fetchSliceAsCloud()

DeviceArray< Point > kfusion::cuda::TsdfVolume::fetchSliceAsCloud ( DeviceArray< Point > &  cloud_buffer,
const kfusion::tsdf_buffer buffer,
const Vec3i  minBounds,
const Vec3i  maxBounds,
const Vec3i  globalShift 
) 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.

Definition at line 184 of file tsdf_volume.cpp.

◆ getCoord()

ushort2 * kfusion::cuda::TsdfVolume::getCoord ( int  x,
int  y,
int  z,
int  dim_x,
int  dim_y 
)

Definition at line 57 of file tsdf_volume.cpp.

◆ getDims()

Vec3i kfusion::cuda::TsdfVolume::getDims ( ) const

Definition at line 33 of file tsdf_volume.cpp.

◆ getGradientDeltaFactor()

float kfusion::cuda::TsdfVolume::getGradientDeltaFactor ( ) const

Definition at line 68 of file tsdf_volume.cpp.

◆ getGridOrigin()

Vec3i kfusion::cuda::TsdfVolume::getGridOrigin ( ) const

◆ getMaxWeight()

int kfusion::cuda::TsdfVolume::getMaxWeight ( ) const

Definition at line 62 of file tsdf_volume.cpp.

◆ getPose()

Affine3f kfusion::cuda::TsdfVolume::getPose ( ) const

Definition at line 64 of file tsdf_volume.cpp.

◆ getRaycastStepFactor()

float kfusion::cuda::TsdfVolume::getRaycastStepFactor ( ) const

Definition at line 66 of file tsdf_volume.cpp.

◆ getSize()

Vec3f kfusion::cuda::TsdfVolume::getSize ( ) const

Definition at line 43 of file tsdf_volume.cpp.

◆ getTruncDist()

float kfusion::cuda::TsdfVolume::getTruncDist ( ) const

Definition at line 48 of file tsdf_volume.cpp.

◆ getVoxelSize()

Vec3f kfusion::cuda::TsdfVolume::getVoxelSize ( ) const

Definition at line 36 of file tsdf_volume.cpp.

◆ integrate()

void kfusion::cuda::TsdfVolume::integrate ( const Dists dists,
tsdf_buffer buffer,
const Affine3f camera_pose,
const Intr intr 
)
virtual

Definition at line 96 of file tsdf_volume.cpp.

◆ raycast() [1/2]

void kfusion::cuda::TsdfVolume::raycast ( const Affine3f camera_pose,
tsdf_buffer buffer,
const Intr intr,
Cloud points,
Normals normals 
)
virtual

Definition at line 129 of file tsdf_volume.cpp.

◆ raycast() [2/2]

void kfusion::cuda::TsdfVolume::raycast ( const Affine3f camera_pose,
tsdf_buffer buffer,
const Intr intr,
Depth depth,
Normals normals 
)
virtual

Definition at line 110 of file tsdf_volume.cpp.

◆ setGradientDeltaFactor()

void kfusion::cuda::TsdfVolume::setGradientDeltaFactor ( float  factor)

Definition at line 69 of file tsdf_volume.cpp.

◆ setGridOrigin()

void kfusion::cuda::TsdfVolume::setGridOrigin ( const Vec3i origin)

◆ setMaxWeight()

void kfusion::cuda::TsdfVolume::setMaxWeight ( int  weight)

Definition at line 63 of file tsdf_volume.cpp.

◆ setPose()

void kfusion::cuda::TsdfVolume::setPose ( const Affine3f pose)

Definition at line 65 of file tsdf_volume.cpp.

◆ setRaycastStepFactor()

void kfusion::cuda::TsdfVolume::setRaycastStepFactor ( float  factor)

Definition at line 67 of file tsdf_volume.cpp.

◆ setSize()

void kfusion::cuda::TsdfVolume::setSize ( const Vec3f size)

Definition at line 45 of file tsdf_volume.cpp.

◆ setTruncDist()

void kfusion::cuda::TsdfVolume::setTruncDist ( float  distance)

Definition at line 50 of file tsdf_volume.cpp.

◆ swap()

void kfusion::cuda::TsdfVolume::swap ( CudaData data)

Definition at line 70 of file tsdf_volume.cpp.

Member Data Documentation

◆ data_

CudaData kfusion::cuda::TsdfVolume::data_
private

Definition at line 86 of file tsdf_volume.hpp.

◆ dims_

Vec3i kfusion::cuda::TsdfVolume::dims_
private

Definition at line 90 of file tsdf_volume.hpp.

◆ gradient_delta_factor_

float kfusion::cuda::TsdfVolume::gradient_delta_factor_
private

Definition at line 94 of file tsdf_volume.hpp.

◆ max_weight_

int kfusion::cuda::TsdfVolume::max_weight_
private

Definition at line 89 of file tsdf_volume.hpp.

◆ pose_

Affine3f kfusion::cuda::TsdfVolume::pose_
private

Definition at line 92 of file tsdf_volume.hpp.

◆ raycast_step_factor_

float kfusion::cuda::TsdfVolume::raycast_step_factor_
private

Definition at line 95 of file tsdf_volume.hpp.

◆ size_

Vec3f kfusion::cuda::TsdfVolume::size_
private

Definition at line 91 of file tsdf_volume.hpp.

◆ trunc_dist_

float kfusion::cuda::TsdfVolume::trunc_dist_
private

Definition at line 88 of file tsdf_volume.hpp.


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


lvr2
Author(s): Thomas Wiemann , Sebastian Pütz , Alexander Mock , Lars Kiesow , Lukas Kalbertodt , Tristan Igelbrink , Johan M. von Behren , Dominik Feldschnieders , Alexander Löhr
autogenerated on Wed Mar 2 2022 00:37:26