Point Cloud Library (PCL)  1.14.0-dev
Classes | Typedefs | Enumerations | Functions | Variables
pcl::device::kinfuLS Namespace Reference

Classes

struct  Intr
 Camera intrinsics structure. More...
 
struct  Mat33
 3x3 Matrix for device code More...
 
struct  Eigen33
 
struct  Block
 
struct  Warp
 
struct  Emulation
 
struct  LightSource
 Light source collection. More...
 
struct  float8
 
struct  float12
 

Typedefs

using ushort = unsigned short
 
using MapArr = DeviceArray2D< float >
 
using DepthMap = DeviceArray2D< ushort >
 
using PointType = float4
 

Enumerations

enum  ScanKind { exclusive , inclusive }
 

Functions

__device__ __forceinline__ void pack_tsdf (float tsdf, int weight, short2 &value)
 
__device__ __forceinline__ void unpack_tsdf (short2 value, float &tsdf, int &weight)
 
__device__ __forceinline__ float unpack_tsdf (short2 value)
 
__device__ __forceinline__ float3 operator* (const Mat33 &m, const float3 &vec)
 
template<ScanKind Kind, class T >
__device__ __forceinline__ T scan_warp (volatile T *ptr, const unsigned int idx=threadIdx.x)
 
template<class T >
__device__ __host__ __forceinline__ void swap (T &a, T &b)
 
__device__ __forceinline__ float dot (const float3 &v1, const float3 &v2)
 
__device__ __forceinline__ float3 & operator+= (float3 &vec, const float &v)
 
__device__ __forceinline__ float3 operator+ (const float3 &v1, const float3 &v2)
 
__device__ __forceinline__ float3 & operator*= (float3 &vec, const float &v)
 
__device__ __forceinline__ float3 operator- (const float3 &v1, const float3 &v2)
 
__device__ __forceinline__ float3 operator* (const float3 &v1, const float &v)
 
__device__ __forceinline__ float norm (const float3 &v)
 
__device__ __forceinline__ float3 normalized (const float3 &v)
 
__device__ __host__ __forceinline__ float3 cross (const float3 &v1, const float3 &v2)
 
__device__ __forceinline__ void computeRoots2 (const float &b, const float &c, float3 &roots)
 
__device__ __forceinline__ void computeRoots3 (float c0, float c1, float c2, float3 &roots)
 
void bilateralFilter (const DepthMap &src, DepthMap &dst)
 Performs bilateral filtering of disparity map. More...
 
void pyrDown (const DepthMap &src, DepthMap &dst)
 Computes depth pyramid. More...
 
void createVMap (const Intr &intr, const DepthMap &depth, MapArr &vmap)
 Computes vertex map. More...
 
void createNMap (const MapArr &vmap, MapArr &nmap)
 Computes normal map using cross product. More...
 
void computeNormalsEigen (const MapArr &vmap, MapArr &nmap)
 Computes normal map using Eigen/PCA approach. More...
 
void transformMaps (const MapArr &vmap_src, const MapArr &nmap_src, const Mat33 &Rmat, const float3 &tvec, MapArr &vmap_dst, MapArr &nmap_dst)
 Performs affine transform of vertex and normal maps. More...
 
void truncateDepth (DepthMap &depth, float max_distance)
 Performs depth truncation. More...
 
void findCoresp (const MapArr &vmap_g_curr, const MapArr &nmap_g_curr, const Mat33 &Rprev_inv, const float3 &tprev, const Intr &intr, const MapArr &vmap_g_prev, const MapArr &nmap_g_prev, float distThres, float angleThres, PtrStepSz< short2 > coresp)
 (now it's extra code) Computes corespondances map More...
 
void estimateTransform (const MapArr &v_dst, const MapArr &n_dst, const MapArr &v_src, const PtrStepSz< short2 > &coresp, DeviceArray2D< float > &gbuf, DeviceArray< float > &mbuf, float *matrixA_host, float *vectorB_host)
 (now it's extra code) Computation Ax=b for ICP iteration More...
 
void estimateCombined (const Mat33 &Rcurr, const float3 &tcurr, const MapArr &vmap_curr, const MapArr &nmap_curr, const Mat33 &Rprev_inv, const float3 &tprev, const Intr &intr, const MapArr &vmap_g_prev, const MapArr &nmap_g_prev, float distThres, float angleThres, DeviceArray2D< float > &gbuf, DeviceArray< float > &mbuf, float *matrixA_host, float *vectorB_host)
 Computation Ax=b for ICP iteration. More...
 
void estimateCombined (const Mat33 &Rcurr, const float3 &tcurr, const MapArr &vmap_curr, const MapArr &nmap_curr, const Mat33 &Rprev_inv, const float3 &tprev, const Intr &intr, const MapArr &vmap_g_prev, const MapArr &nmap_g_prev, float distThres, float angleThres, DeviceArray2D< double > &gbuf, DeviceArray< double > &mbuf, double *matrixA_host, double *vectorB_host)
 Computation Ax=b for ICP iteration. More...
 
PCL_EXPORTS void initVolume (PtrStep< short2 > array)
 Perform tsdf volume initialization. More...
 
void integrateTsdfVolume (const PtrStepSz< ushort > &depth_raw, const Intr &intr, const float3 &volume_size, const Mat33 &Rcurr_inv, const float3 &tcurr, float tranc_dist, PtrStep< short2 > volume)
 Performs Tsfg volume uptation (extra obsolete now) More...
 
PCL_EXPORTS void integrateTsdfVolume (const PtrStepSz< ushort > &depth, const Intr &intr, const float3 &volume_size, const Mat33 &Rcurr_inv, const float3 &tcurr, float tranc_dist, PtrStep< short2 > volume, const pcl::gpu::kinfuLS::tsdf_buffer *buffer, DeviceArray2D< float > &depthScaled)
 Function that integrates volume if volume element contains: 2 bytes for round(tsdf*SHORT_MAX) and 2 bytes for integer weight. More...
 
PCL_EXPORTS void clearTSDFSlice (PtrStep< short2 > volume, pcl::gpu::kinfuLS::tsdf_buffer *buffer, int shiftX, int shiftY, int shiftZ)
 Function that clears the TSDF values. More...
 
void initColorVolume (PtrStep< uchar4 > color_volume)
 Initialized color volume. More...
 
void updateColorVolume (const Intr &intr, float tranc_dist, const Mat33 &R_inv, const float3 &t, const MapArr &vmap, const PtrStepSz< uchar3 > &colors, const float3 &volume_size, PtrStep< uchar4 > color_volume, int max_weight=1)
 Performs integration in color volume. More...
 
void raycast (const Intr &intr, const Mat33 &Rcurr, const float3 &tcurr, float tranc_dist, const float3 &volume_size, const PtrStep< short2 > &volume, const pcl::gpu::kinfuLS::tsdf_buffer *buffer, MapArr &vmap, MapArr &nmap)
 Generation vertex and normal maps from volume for current camera pose. More...
 
void generateImage (const MapArr &vmap, const MapArr &nmap, const LightSource &light, PtrStepSz< uchar3 > dst)
 Renders 3D image of the scene. More...
 
void generateDepth (const Mat33 &R_inv, const float3 &t, const MapArr &vmap, DepthMap &dst)
 Renders depth image from give pose. More...
 
void paint3DView (const PtrStep< uchar3 > &colors, PtrStepSz< uchar3 > dst, float colors_weight=0.5f)
 Paints 3D view with color map. More...
 
void resizeVMap (const MapArr &input, MapArr &output)
 Performs resize of vertex map to next pyramid level by averaging each four points. More...
 
void resizeNMap (const MapArr &input, MapArr &output)
 Performs resize of vertex map to next pyramid level by averaging each four normals. More...
 
void pushCloudAsSliceGPU (const PtrStep< short2 > &volume, pcl::gpu::DeviceArray< PointType > cloud_gpu, const pcl::gpu::kinfuLS::tsdf_buffer *buffer)
 Loads the values of a tsdf point cloud to the tsdf volume in GPU. More...
 
PCL_EXPORTS std::size_t extractCloud (const PtrStep< short2 > &volume, const float3 &volume_size, PtrSz< PointType > output)
 Perform point cloud extraction from tsdf volume. More...
 
PCL_EXPORTS std::size_t extractSliceAsCloud (const PtrStep< short2 > &volume, const float3 &volume_size, const pcl::gpu::kinfuLS::tsdf_buffer *buffer, const int shiftX, const int shiftY, const int shiftZ, PtrSz< PointType > output_xyz, PtrSz< float > output_intensities)
 Perform point cloud extraction of a slice from tsdf volume. More...
 
template<typename NormalType >
void extractNormals (const PtrStep< short2 > &volume, const float3 &volume_size, const PtrSz< PointType > &input, NormalType *output)
 Performs normals computation for given points using tsdf volume. More...
 
void exctractColors (const PtrStep< uchar4 > &color_volume, const float3 &volume_size, const PtrSz< PointType > &points, uchar4 *colors)
 Performs colors extraction from color volume. More...
 
template<typename T >
void convert (const MapArr &vmap, DeviceArray2D< T > &output)
 Conversion from SOA to AOS. More...
 
void mergePointNormal (const DeviceArray< float4 > &cloud, const DeviceArray< float8 > &normals, const DeviceArray< float12 > &output)
 Merges pcl::PointXYZ and pcl::Normal to PointNormal. More...
 
bool valid_host (float value)
 Check for qnan (unused now) More...
 
void sync ()
 synchronizes CUDA execution More...
 
template<class D , class Matx >
D & device_cast (Matx &matx)
 
void bindTextures (const int *edgeBuf, const int *triBuf, const int *numVertsBuf)
 Binds marching cubes tables to texture references. More...
 
void unbindTextures ()
 Unbinds. More...
 
int getOccupiedVoxels (const PtrStep< short2 > &volume, DeviceArray2D< int > &occupied_voxels)
 Scans tsdf volume and retrieves occupied voxels. More...
 
int computeOffsetsAndTotalVertexes (DeviceArray2D< int > &occupied_voxels)
 Computes total number of vertices for all voxels and offsets of vertices in final triangle array. More...
 
void generateTriangles (const PtrStep< short2 > &volume, const DeviceArray2D< int > &occupied_voxels, const float3 &volume_size, DeviceArray< PointType > &output)
 Generates final triangle array. More...
 

Variables

constexpr int DIVISOR = std::numeric_limits<short>::max()
 
constexpr float HEIGHT = 480.0f
 
constexpr float WIDTH = 640.0f
 
constexpr int VOLUME_X = 512
 
constexpr int VOLUME_Y = 512
 
constexpr int VOLUME_Z = 512
 
constexpr float FOCAL_LENGTH = 575.816f
 
constexpr float VOLUME_SIZE = 3.0f
 
constexpr float DISTANCE_THRESHOLD = 1.5f
 
constexpr int SNAPSHOT_RATE = 45
 

Typedef Documentation

◆ DepthMap

Definition at line 58 of file device.h.

◆ MapArr

Definition at line 57 of file device.h.

◆ PointType

using pcl::device::kinfuLS::PointType = typedef float4

Definition at line 59 of file device.h.

◆ ushort

using pcl::device::kinfuLS::ushort = typedef unsigned short

Definition at line 56 of file device.h.

Enumeration Type Documentation

◆ ScanKind

Enumerator
exclusive 
inclusive 

Definition at line 87 of file device.hpp.

Function Documentation

◆ bilateralFilter()

void pcl::device::kinfuLS::bilateralFilter ( const DepthMap src,
DepthMap dst 
)

Performs bilateral filtering of disparity map.

Parameters
[in]srcsource map
[out]dstoutput map

◆ bindTextures()

void pcl::device::kinfuLS::bindTextures ( const int *  edgeBuf,
const int *  triBuf,
const int *  numVertsBuf 
)

Binds marching cubes tables to texture references.

◆ clearTSDFSlice()

PCL_EXPORTS void pcl::device::kinfuLS::clearTSDFSlice ( PtrStep< short2 >  volume,
pcl::gpu::kinfuLS::tsdf_buffer buffer,
int  shiftX,
int  shiftY,
int  shiftZ 
)

Function that clears the TSDF values.

The clearing takes place from the origin (in indices) to an offset in X,Y,Z values accordingly

Parameters
[in]volumePointer to TSDF volume in GPU
[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 that will be cleared from the TSDF volume. The clearing start from buffer.OriginX and stops in OriginX + shiftX
[in]shiftYOffset in indices that will be cleared from the TSDF volume. The clearing start from buffer.OriginY and stops in OriginY + shiftY
[in]shiftZOffset in indices that will be cleared from the TSDF volume. The clearing start from buffer.OriginZ and stops in OriginZ + shiftZ

◆ computeNormalsEigen()

void pcl::device::kinfuLS::computeNormalsEigen ( const MapArr vmap,
MapArr nmap 
)

Computes normal map using Eigen/PCA approach.

Parameters
[in]vmapvertex map
[out]nmapnormal map

◆ computeOffsetsAndTotalVertexes()

int pcl::device::kinfuLS::computeOffsetsAndTotalVertexes ( DeviceArray2D< int > &  occupied_voxels)

Computes total number of vertices for all voxels and offsets of vertices in final triangle array.

Parameters
[out]occupied_voxelsbuffer with occupied voxels. The function fulfills 3nd only with offsets
Returns
total number of vertices

◆ computeRoots2()

__device__ __forceinline__ void pcl::device::kinfuLS::computeRoots2 ( const float &  b,
const float &  c,
float3 &  roots 
)

Definition at line 114 of file utils.hpp.

Referenced by computeRoots3().

◆ computeRoots3()

__device__ __forceinline__ void pcl::device::kinfuLS::computeRoots3 ( float  c0,
float  c1,
float  c2,
float3 &  roots 
)

Definition at line 128 of file utils.hpp.

References computeRoots2(), and swap().

Referenced by pcl::device::kinfuLS::Eigen33::compute().

◆ convert()

template<typename T >
void pcl::device::kinfuLS::convert ( const MapArr vmap,
DeviceArray2D< T > &  output 
)

Conversion from SOA to AOS.

Parameters
[in]vmapSOA map
[out]outputArray of 3D points. Can be float4 or float8.

◆ createNMap()

void pcl::device::kinfuLS::createNMap ( const MapArr vmap,
MapArr nmap 
)

Computes normal map using cross product.

Parameters
[in]vmapvertex map
[out]nmapnormal map

◆ createVMap()

void pcl::device::kinfuLS::createVMap ( const Intr intr,
const DepthMap depth,
MapArr vmap 
)

Computes vertex map.

Parameters
[in]intrdepth camera intrinsics
[in]depthdepth
[out]vmapvertex map

◆ cross()

__device__ __host__ __forceinline__ float3 pcl::device::kinfuLS::cross ( const float3 &  v1,
const float3 &  v2 
)

Definition at line 109 of file utils.hpp.

Referenced by pcl::device::kinfuLS::Eigen33::compute().

◆ device_cast()

template<class D , class Matx >
D& pcl::device::kinfuLS::device_cast ( Matx &  matx)

Definition at line 415 of file internal.h.

◆ dot()

__device__ __forceinline__ float pcl::device::kinfuLS::dot ( const float3 &  v1,
const float3 &  v2 
)

Definition at line 61 of file utils.hpp.

Referenced by pcl::device::kinfuLS::Eigen33::compute(), norm(), normalized(), and operator*().

◆ estimateCombined() [1/2]

void pcl::device::kinfuLS::estimateCombined ( const Mat33 Rcurr,
const float3 &  tcurr,
const MapArr vmap_curr,
const MapArr nmap_curr,
const Mat33 Rprev_inv,
const float3 &  tprev,
const Intr intr,
const MapArr vmap_g_prev,
const MapArr nmap_g_prev,
float  distThres,
float  angleThres,
DeviceArray2D< double > &  gbuf,
DeviceArray< double > &  mbuf,
double *  matrixA_host,
double *  vectorB_host 
)

Computation Ax=b for ICP iteration.

Parameters
[in]RcurrRotation of current camera pose guess
[in]tcurrtranslation of current camera pose guess
[in]vmap_currcurrent vertex map in camera coo space
[in]nmap_currcurrent vertex map in camera coo space
[in]Rprev_invinverse camera rotation at previous pose
[in]tprevcamera translation at previous pose
[in]intrcamera intrinsics
[in]vmap_g_prevprevious vertex map in global coo space
[in]nmap_g_prevprevious vertex map in global coo space
[in]distThresdistance filtering threshold
[in]angleThresangle filtering threshold. Represents sine of angle between normals
[out]gbuftemp buffer for GPU reduction
[out]mbufoutput GPU buffer for matrix computed
[out]matrixA_hostA
[out]vectorB_hostb

◆ estimateCombined() [2/2]

void pcl::device::kinfuLS::estimateCombined ( const Mat33 Rcurr,
const float3 &  tcurr,
const MapArr vmap_curr,
const MapArr nmap_curr,
const Mat33 Rprev_inv,
const float3 &  tprev,
const Intr intr,
const MapArr vmap_g_prev,
const MapArr nmap_g_prev,
float  distThres,
float  angleThres,
DeviceArray2D< float > &  gbuf,
DeviceArray< float > &  mbuf,
float *  matrixA_host,
float *  vectorB_host 
)

Computation Ax=b for ICP iteration.

Parameters
[in]RcurrRotation of current camera pose guess
[in]tcurrtranslation of current camera pose guess
[in]vmap_currcurrent vertex map in camera coo space
[in]nmap_currcurrent vertex map in camera coo space
[in]Rprev_invinverse camera rotation at previous pose
[in]tprevcamera translation at previous pose
[in]intrcamera intrinsics
[in]vmap_g_prevprevious vertex map in global coo space
[in]nmap_g_prevprevious vertex map in global coo space
[in]distThresdistance filtering threshold
[in]angleThresangle filtering threshold. Represents sine of angle between normals
[out]gbuftemp buffer for GPU reduction
[out]mbufoutput GPU buffer for matrix computed
[out]matrixA_hostA
[out]vectorB_hostb

◆ estimateTransform()

void pcl::device::kinfuLS::estimateTransform ( const MapArr v_dst,
const MapArr n_dst,
const MapArr v_src,
const PtrStepSz< short2 > &  coresp,
DeviceArray2D< float > &  gbuf,
DeviceArray< float > &  mbuf,
float *  matrixA_host,
float *  vectorB_host 
)

(now it's extra code) Computation Ax=b for ICP iteration

Parameters
[in]v_dstdestination vertex map (previous frame cloud)
[in]n_dstdestination normal map (previous frame normals)
[in]v_srcsource normal map (current frame cloud)
[in]corespCorespondances
[out]gbuftemp buffer for GPU reduction
[out]mbufoutput GPU buffer for matrix computed
[out]matrixA_hostA
[out]vectorB_hostb

◆ exctractColors()

void pcl::device::kinfuLS::exctractColors ( const PtrStep< uchar4 > &  color_volume,
const float3 &  volume_size,
const PtrSz< PointType > &  points,
uchar4 *  colors 
)

Performs colors extraction from color volume.

Parameters
[in]color_volumecolor volume
[in]volume_sizevolume size
[in]pointspoints for which color are computed
[out]colorsoutput array with colors.

◆ extractCloud()

PCL_EXPORTS std::size_t pcl::device::kinfuLS::extractCloud ( const PtrStep< short2 > &  volume,
const float3 &  volume_size,
PtrSz< PointType output 
)

Perform point cloud extraction from tsdf volume.

Parameters
[in]volumetsdf volume
[in]volume_sizesize of the volume
[out]outputbuffer large enough to store point cloud
Returns
number of point stored to passed buffer

◆ extractNormals()

template<typename NormalType >
void pcl::device::kinfuLS::extractNormals ( const PtrStep< short2 > &  volume,
const float3 &  volume_size,
const PtrSz< PointType > &  input,
NormalType output 
)

Performs normals computation for given points using tsdf volume.

Parameters
[in]volumetsdf volume
[in]volume_sizevolume size
[in]inputpoints where normals are computed
[out]outputnormals. Could be float4 or float8. If for a point normal can't be computed, such normal is marked as nan.

◆ extractSliceAsCloud()

PCL_EXPORTS std::size_t pcl::device::kinfuLS::extractSliceAsCloud ( const PtrStep< short2 > &  volume,
const float3 &  volume_size,
const pcl::gpu::kinfuLS::tsdf_buffer buffer,
const int  shiftX,
const int  shiftY,
const int  shiftZ,
PtrSz< PointType output_xyz,
PtrSz< float >  output_intensities 
)

Perform point cloud extraction of a slice from tsdf volume.

Parameters
[in]volumetsdf volume on GPU
[in]volume_sizesize of the volume
[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 that will be cleared from the TSDF volume. The clearing start from buffer.OriginX and stops in OriginX + shiftX
[in]shiftYOffset in indices that will be cleared from the TSDF volume. The clearing start from buffer.OriginY and stops in OriginY + shiftY
[in]shiftZOffset in indices that will be cleared from the TSDF volume. The clearing start from buffer.OriginZ and stops in OriginZ + shiftZ
[out]output_xyzbuffer large enough to store point cloud xyz values
[out]output_intensitiesbuffer large enough to store point cloud intensity values
Returns
number of point stored to passed buffer

◆ findCoresp()

void pcl::device::kinfuLS::findCoresp ( const MapArr vmap_g_curr,
const MapArr nmap_g_curr,
const Mat33 Rprev_inv,
const float3 &  tprev,
const Intr intr,
const MapArr vmap_g_prev,
const MapArr nmap_g_prev,
float  distThres,
float  angleThres,
PtrStepSz< short2 >  coresp 
)

(now it's extra code) Computes corespondances map

Parameters
[in]vmap_g_currcurrent vertex map in global coo space
[in]nmap_g_currcurrent normals map in global coo space
[in]Rprev_invinverse camera rotation at previous pose
[in]tprevcamera translation at previous pose
[in]intrcamera intrinsics
[in]vmap_g_prevprevious vertex map in global coo space
[in]nmap_g_prevprevious vertex map in global coo space
[in]distThresdistance filtering threshold
[in]angleThresangle filtering threshold. Represents sine of angle between normals
[out]coresp

◆ generateDepth()

void pcl::device::kinfuLS::generateDepth ( const Mat33 R_inv,
const float3 &  t,
const MapArr vmap,
DepthMap dst 
)

Renders depth image from give pose.

Parameters
[in]R_invinverse camera rotation
[in]tcamera translation
[in]vmapvertex map
[out]dstbuffer where depth is generated

◆ generateImage()

void pcl::device::kinfuLS::generateImage ( const MapArr vmap,
const MapArr nmap,
const LightSource light,
PtrStepSz< uchar3 >  dst 
)

Renders 3D image of the scene.

Parameters
[in]vmapvertex map
[in]nmapnormals map
[in]lightpose of light source
[out]dstbuffer where image is generated

◆ generateTriangles()

void pcl::device::kinfuLS::generateTriangles ( const PtrStep< short2 > &  volume,
const DeviceArray2D< int > &  occupied_voxels,
const float3 &  volume_size,
DeviceArray< PointType > &  output 
)

Generates final triangle array.

Parameters
[in]volumetsdf volume
[in]occupied_voxelsoccupied voxel ids (first row), number of vertices(second row), offsets(third row).
[in]volume_sizevolume size in meters
[out]outputtriangle array

◆ getOccupiedVoxels()

int pcl::device::kinfuLS::getOccupiedVoxels ( const PtrStep< short2 > &  volume,
DeviceArray2D< int > &  occupied_voxels 
)

Scans tsdf volume and retrieves occupied voxels.

Parameters
[in]volumetsdf volume
[out]occupied_voxelsbuffer for occupied voxels. The function fulfills first row with voxel ids and second row with number of vertices.
Returns
number of voxels in the buffer

◆ initColorVolume()

void pcl::device::kinfuLS::initColorVolume ( PtrStep< uchar4 >  color_volume)

Initialized color volume.

Parameters
[out]color_volumecolor volume for initialization

◆ initVolume()

PCL_EXPORTS void pcl::device::kinfuLS::initVolume ( PtrStep< short2 >  array)

Perform tsdf volume initialization.

Parameters
[out]arrayvolume to be initialized

◆ integrateTsdfVolume() [1/2]

PCL_EXPORTS void pcl::device::kinfuLS::integrateTsdfVolume ( const PtrStepSz< ushort > &  depth,
const Intr intr,
const float3 &  volume_size,
const Mat33 Rcurr_inv,
const float3 &  tcurr,
float  tranc_dist,
PtrStep< short2 >  volume,
const pcl::gpu::kinfuLS::tsdf_buffer buffer,
DeviceArray2D< float > &  depthScaled 
)

Function that integrates volume if volume element contains: 2 bytes for round(tsdf*SHORT_MAX) and 2 bytes for integer weight.

Parameters
[in]depthKinect depth image
[in]intrcamera intrinsics
[in]volume_sizesize of volume in mm
[in]Rcurr_invinverse rotation for current camera pose
[in]tcurrtranslation for current camera pose
[in]tranc_disttsdf truncation distance
[in]volumetsdf volume to be updated
[in]buffercyclical buffer structure
[out]depthScaledBuffer for scaled depth along ray

◆ integrateTsdfVolume() [2/2]

void pcl::device::kinfuLS::integrateTsdfVolume ( const PtrStepSz< ushort > &  depth_raw,
const Intr intr,
const float3 &  volume_size,
const Mat33 Rcurr_inv,
const float3 &  tcurr,
float  tranc_dist,
PtrStep< short2 >  volume 
)

Performs Tsfg volume uptation (extra obsolete now)

Parameters
[in]depth_rawKinect depth image
[in]intrcamera intrinsics
[in]volume_sizesize of volume in mm
[in]Rcurr_invinverse rotation for current camera pose
[in]tcurrtranslation for current camera pose
[in]tranc_disttsdf truncation distance
[in]volumetsdf volume to be updated

◆ mergePointNormal()

void pcl::device::kinfuLS::mergePointNormal ( const DeviceArray< float4 > &  cloud,
const DeviceArray< float8 > &  normals,
const DeviceArray< float12 > &  output 
)

Merges pcl::PointXYZ and pcl::Normal to PointNormal.

Parameters
[in]cloudpoints cloud
[in]normalsnormals cloud
[out]outputarray of PointNomals.

◆ norm()

__device__ __forceinline__ float pcl::device::kinfuLS::norm ( const float3 &  v)

Definition at line 97 of file utils.hpp.

References dot().

◆ normalized()

__device__ __forceinline__ float3 pcl::device::kinfuLS::normalized ( const float3 &  v)

Definition at line 103 of file utils.hpp.

References dot().

Referenced by pcl::device::kinfuLS::Eigen33::compute().

◆ operator*() [1/2]

__device__ __forceinline__ float3 pcl::device::kinfuLS::operator* ( const float3 &  v1,
const float &  v 
)

Definition at line 91 of file utils.hpp.

◆ operator*() [2/2]

__device__ __forceinline__ float3 pcl::device::kinfuLS::operator* ( const Mat33 m,
const float3 &  vec 
)

Definition at line 78 of file device.hpp.

References pcl::device::kinfuLS::Mat33::data, and dot().

◆ operator*=()

__device__ __forceinline__ float3& pcl::device::kinfuLS::operator*= ( float3 &  vec,
const float &  v 
)

Definition at line 79 of file utils.hpp.

◆ operator+()

__device__ __forceinline__ float3 pcl::device::kinfuLS::operator+ ( const float3 &  v1,
const float3 &  v2 
)

Definition at line 73 of file utils.hpp.

◆ operator+=()

__device__ __forceinline__ float3& pcl::device::kinfuLS::operator+= ( float3 &  vec,
const float &  v 
)

Definition at line 67 of file utils.hpp.

◆ operator-()

__device__ __forceinline__ float3 pcl::device::kinfuLS::operator- ( const float3 &  v1,
const float3 &  v2 
)

Definition at line 85 of file utils.hpp.

◆ pack_tsdf()

__device__ __forceinline__ void pcl::device::kinfuLS::pack_tsdf ( float  tsdf,
int  weight,
short2 &  value 
)

Definition at line 56 of file device.hpp.

References DIVISOR.

◆ paint3DView()

void pcl::device::kinfuLS::paint3DView ( const PtrStep< uchar3 > &  colors,
PtrStepSz< uchar3 >  dst,
float  colors_weight = 0.5f 
)

Paints 3D view with color map.

Parameters
[in]colorsrgb color frame from OpenNI
[out]dstoutput 3D view
[in]colors_weightweight for colors

◆ pushCloudAsSliceGPU()

void pcl::device::kinfuLS::pushCloudAsSliceGPU ( const PtrStep< short2 > &  volume,
pcl::gpu::DeviceArray< PointType cloud_gpu,
const pcl::gpu::kinfuLS::tsdf_buffer buffer 
)

Loads the values of a tsdf point cloud to the tsdf volume in GPU.

Parameters
[in]volumetsdf volume
[in]cloud_gpucontains the data to be pushed to the tsdf volume
[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.

◆ pyrDown()

void pcl::device::kinfuLS::pyrDown ( const DepthMap src,
DepthMap dst 
)

Computes depth pyramid.

Parameters
[in]srcsource
[out]dstdestination

◆ raycast()

void pcl::device::kinfuLS::raycast ( const Intr intr,
const Mat33 Rcurr,
const float3 &  tcurr,
float  tranc_dist,
const float3 &  volume_size,
const PtrStep< short2 > &  volume,
const pcl::gpu::kinfuLS::tsdf_buffer buffer,
MapArr vmap,
MapArr nmap 
)

Generation vertex and normal maps from volume for current camera pose.

Parameters
[in]intrcamera intrinsices
[in]Rcurrcurrent rotation
[in]tcurrcurrent translation
[in]tranc_distvolume truncation distance
[in]volume_sizevolume size in mm
[in]volumetsdf volume
[in]buffercyclical buffer structure
[out]vmapoutput vertex map
[out]nmapoutput normals map

◆ resizeNMap()

void pcl::device::kinfuLS::resizeNMap ( const MapArr input,
MapArr output 
)

Performs resize of vertex map to next pyramid level by averaging each four normals.

Parameters
[in]inputnormal map
[out]outputvertex map

◆ resizeVMap()

void pcl::device::kinfuLS::resizeVMap ( const MapArr input,
MapArr output 
)

Performs resize of vertex map to next pyramid level by averaging each four points.

Parameters
[in]inputvertext map
[out]outputresized vertex map

◆ scan_warp()

template<ScanKind Kind, class T >
__device__ __forceinline__ T pcl::device::kinfuLS::scan_warp ( volatile T *  ptr,
const unsigned int  idx = threadIdx.x 
)

Definition at line 91 of file device.hpp.

References inclusive.

◆ swap()

template<class T >
__device__ __host__ __forceinline__ void pcl::device::kinfuLS::swap ( T &  a,
T &  b 
)

Definition at line 55 of file utils.hpp.

Referenced by computeRoots3().

◆ sync()

void pcl::device::kinfuLS::sync ( )
inline

synchronizes CUDA execution

Definition at line 411 of file internal.h.

◆ transformMaps()

void pcl::device::kinfuLS::transformMaps ( const MapArr vmap_src,
const MapArr nmap_src,
const Mat33 Rmat,
const float3 &  tvec,
MapArr vmap_dst,
MapArr nmap_dst 
)

Performs affine transform of vertex and normal maps.

Parameters
[in]vmap_srcsource vertex map
[in]nmap_srcsource vertex map
[in]RmatRotation mat
[in]tvectranslation
[out]vmap_dstdestination vertex map
[out]nmap_dstdestination vertex map

◆ truncateDepth()

void pcl::device::kinfuLS::truncateDepth ( DepthMap depth,
float  max_distance 
)

Performs depth truncation.

Parameters
[out]depthdepth map to truncation
[in]max_distancetruncation threshold, values that are higher than the threshold are reset to zero (means not measurement)

◆ unbindTextures()

void pcl::device::kinfuLS::unbindTextures ( )

Unbinds.

◆ unpack_tsdf() [1/2]

__device__ __forceinline__ float pcl::device::kinfuLS::unpack_tsdf ( short2  value)

Definition at line 71 of file device.hpp.

References DIVISOR.

◆ unpack_tsdf() [2/2]

__device__ __forceinline__ void pcl::device::kinfuLS::unpack_tsdf ( short2  value,
float &  tsdf,
int &  weight 
)

Definition at line 64 of file device.hpp.

References DIVISOR.

◆ updateColorVolume()

void pcl::device::kinfuLS::updateColorVolume ( const Intr intr,
float  tranc_dist,
const Mat33 R_inv,
const float3 &  t,
const MapArr vmap,
const PtrStepSz< uchar3 > &  colors,
const float3 &  volume_size,
PtrStep< uchar4 >  color_volume,
int  max_weight = 1 
)

Performs integration in color volume.

Parameters
[in]intrDepth camera intrionsics structure
[in]tranc_disttsdf truncation distance
[in]R_invInverse camera rotation
[in]tcamera translation
[in]vmapRaycasted vertex map
[in]colorsRGB colors for current frame
[in]volume_sizevolume size in meters
[in]color_volumecolor volume to be integrated
[in]max_weightmax weight for running color average. Zero means not average, one means average with prev value, etc.

◆ valid_host()

bool pcl::device::kinfuLS::valid_host ( float  value)
inline

Check for qnan (unused now)

Parameters
[in]value

Definition at line 403 of file internal.h.

Variable Documentation

◆ DISTANCE_THRESHOLD

constexpr float pcl::device::kinfuLS::DISTANCE_THRESHOLD = 1.5f
constexpr

Definition at line 77 of file device.h.

◆ DIVISOR

constexpr int pcl::device::kinfuLS::DIVISOR = std::numeric_limits<short>::max()
constexpr

Definition at line 62 of file device.h.

Referenced by pack_tsdf(), and unpack_tsdf().

◆ FOCAL_LENGTH

constexpr float pcl::device::kinfuLS::FOCAL_LENGTH = 575.816f
constexpr

Definition at line 74 of file device.h.

◆ HEIGHT

constexpr float pcl::device::kinfuLS::HEIGHT = 480.0f
constexpr

Definition at line 65 of file device.h.

◆ SNAPSHOT_RATE

constexpr int pcl::device::kinfuLS::SNAPSHOT_RATE = 45
constexpr

Definition at line 78 of file device.h.

◆ VOLUME_SIZE

constexpr float pcl::device::kinfuLS::VOLUME_SIZE = 3.0f
constexpr

Definition at line 76 of file device.h.

◆ VOLUME_X

constexpr int pcl::device::kinfuLS::VOLUME_X = 512
constexpr

Definition at line 69 of file device.h.

◆ VOLUME_Y

constexpr int pcl::device::kinfuLS::VOLUME_Y = 512
constexpr

Definition at line 70 of file device.h.

◆ VOLUME_Z

constexpr int pcl::device::kinfuLS::VOLUME_Z = 512
constexpr

Definition at line 71 of file device.h.

◆ WIDTH

constexpr float pcl::device::kinfuLS::WIDTH = 640.0f
constexpr

Definition at line 66 of file device.h.