Point Cloud Library (PCL)
1.14.1-dev
|
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 |
using pcl::device::kinfuLS::DepthMap = typedef DeviceArray2D<ushort> |
using pcl::device::kinfuLS::MapArr = typedef DeviceArray2D<float> |
using pcl::device::kinfuLS::PointType = typedef float4 |
using pcl::device::kinfuLS::ushort = typedef unsigned short |
Enumerator | |
---|---|
exclusive | |
inclusive |
Definition at line 87 of file device.hpp.
Performs bilateral filtering of disparity map.
[in] | src | source map |
[out] | dst | output map |
void pcl::device::kinfuLS::bindTextures | ( | const int * | edgeBuf, |
const int * | triBuf, | ||
const int * | numVertsBuf | ||
) |
Binds marching cubes tables to texture references.
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
[in] | volume | Pointer to TSDF volume in GPU |
[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 that will be cleared from the TSDF volume. The clearing start from buffer.OriginX and stops in OriginX + shiftX |
[in] | shiftY | Offset in indices that will be cleared from the TSDF volume. The clearing start from buffer.OriginY and stops in OriginY + shiftY |
[in] | shiftZ | Offset in indices that will be cleared from the TSDF volume. The clearing start from buffer.OriginZ and stops in OriginZ + shiftZ |
Computes normal map using Eigen/PCA approach.
[in] | vmap | vertex map |
[out] | nmap | normal map |
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.
[out] | occupied_voxels | buffer with occupied voxels. The function fulfills 3nd only with offsets |
__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().
__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().
void pcl::device::kinfuLS::convert | ( | const MapArr & | vmap, |
DeviceArray2D< T > & | output | ||
) |
Conversion from SOA to AOS.
[in] | vmap | SOA map |
[out] | output | Array of 3D points. Can be float4 or float8. |
Computes normal map using cross product.
[in] | vmap | vertex map |
[out] | nmap | normal map |
Computes vertex map.
[in] | intr | depth camera intrinsics |
[in] | depth | depth |
[out] | vmap | vertex map |
__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().
D& pcl::device::kinfuLS::device_cast | ( | Matx & | matx | ) |
Definition at line 415 of file internal.h.
__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*().
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.
[in] | Rcurr | Rotation of current camera pose guess |
[in] | tcurr | translation of current camera pose guess |
[in] | vmap_curr | current vertex map in camera coo space |
[in] | nmap_curr | current vertex map in camera coo space |
[in] | Rprev_inv | inverse camera rotation at previous pose |
[in] | tprev | camera translation at previous pose |
[in] | intr | camera intrinsics |
[in] | vmap_g_prev | previous vertex map in global coo space |
[in] | nmap_g_prev | previous vertex map in global coo space |
[in] | distThres | distance filtering threshold |
[in] | angleThres | angle filtering threshold. Represents sine of angle between normals |
[out] | gbuf | temp buffer for GPU reduction |
[out] | mbuf | output GPU buffer for matrix computed |
[out] | matrixA_host | A |
[out] | vectorB_host | b |
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.
[in] | Rcurr | Rotation of current camera pose guess |
[in] | tcurr | translation of current camera pose guess |
[in] | vmap_curr | current vertex map in camera coo space |
[in] | nmap_curr | current vertex map in camera coo space |
[in] | Rprev_inv | inverse camera rotation at previous pose |
[in] | tprev | camera translation at previous pose |
[in] | intr | camera intrinsics |
[in] | vmap_g_prev | previous vertex map in global coo space |
[in] | nmap_g_prev | previous vertex map in global coo space |
[in] | distThres | distance filtering threshold |
[in] | angleThres | angle filtering threshold. Represents sine of angle between normals |
[out] | gbuf | temp buffer for GPU reduction |
[out] | mbuf | output GPU buffer for matrix computed |
[out] | matrixA_host | A |
[out] | vectorB_host | b |
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
[in] | v_dst | destination vertex map (previous frame cloud) |
[in] | n_dst | destination normal map (previous frame normals) |
[in] | v_src | source normal map (current frame cloud) |
[in] | coresp | Corespondances |
[out] | gbuf | temp buffer for GPU reduction |
[out] | mbuf | output GPU buffer for matrix computed |
[out] | matrixA_host | A |
[out] | vectorB_host | b |
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.
[in] | color_volume | color volume |
[in] | volume_size | volume size |
[in] | points | points for which color are computed |
[out] | colors | output array with colors. |
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.
[in] | volume | tsdf volume |
[in] | volume_size | size of the volume |
[out] | output | buffer large enough to store point cloud |
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.
[in] | volume | tsdf volume |
[in] | volume_size | volume size |
[in] | input | points where normals are computed |
[out] | output | normals. Could be float4 or float8. If for a point normal can't be computed, such normal is marked as nan. |
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.
[in] | volume | tsdf volume on GPU |
[in] | volume_size | size of the volume |
[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 that will be cleared from the TSDF volume. The clearing start from buffer.OriginX and stops in OriginX + shiftX |
[in] | shiftY | Offset in indices that will be cleared from the TSDF volume. The clearing start from buffer.OriginY and stops in OriginY + shiftY |
[in] | shiftZ | Offset in indices that will be cleared from the TSDF volume. The clearing start from buffer.OriginZ and stops in OriginZ + shiftZ |
[out] | output_xyz | buffer large enough to store point cloud xyz values |
[out] | output_intensities | buffer large enough to store point cloud intensity values |
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
[in] | vmap_g_curr | current vertex map in global coo space |
[in] | nmap_g_curr | current normals map in global coo space |
[in] | Rprev_inv | inverse camera rotation at previous pose |
[in] | tprev | camera translation at previous pose |
[in] | intr | camera intrinsics |
[in] | vmap_g_prev | previous vertex map in global coo space |
[in] | nmap_g_prev | previous vertex map in global coo space |
[in] | distThres | distance filtering threshold |
[in] | angleThres | angle filtering threshold. Represents sine of angle between normals |
[out] | coresp |
void pcl::device::kinfuLS::generateDepth | ( | const Mat33 & | R_inv, |
const float3 & | t, | ||
const MapArr & | vmap, | ||
DepthMap & | dst | ||
) |
Renders depth image from give pose.
[in] | R_inv | inverse camera rotation |
[in] | t | camera translation |
[in] | vmap | vertex map |
[out] | dst | buffer where depth is generated |
void pcl::device::kinfuLS::generateImage | ( | const MapArr & | vmap, |
const MapArr & | nmap, | ||
const LightSource & | light, | ||
PtrStepSz< uchar3 > | dst | ||
) |
Renders 3D image of the scene.
[in] | vmap | vertex map |
[in] | nmap | normals map |
[in] | light | pose of light source |
[out] | dst | buffer where image is generated |
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.
[in] | volume | tsdf volume |
[in] | occupied_voxels | occupied voxel ids (first row), number of vertices(second row), offsets(third row). |
[in] | volume_size | volume size in meters |
[out] | output | triangle array |
int pcl::device::kinfuLS::getOccupiedVoxels | ( | const PtrStep< short2 > & | volume, |
DeviceArray2D< int > & | occupied_voxels | ||
) |
Scans tsdf volume and retrieves occupied voxels.
[in] | volume | tsdf volume |
[out] | occupied_voxels | buffer for occupied voxels. The function fulfills first row with voxel ids and second row with number of vertices. |
void pcl::device::kinfuLS::initColorVolume | ( | PtrStep< uchar4 > | color_volume | ) |
Initialized color volume.
[out] | color_volume | color volume for initialization |
PCL_EXPORTS void pcl::device::kinfuLS::initVolume | ( | PtrStep< short2 > | array | ) |
Perform tsdf volume initialization.
[out] | array | volume to be initialized |
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.
[in] | depth | Kinect depth image |
[in] | intr | camera intrinsics |
[in] | volume_size | size of volume in mm |
[in] | Rcurr_inv | inverse rotation for current camera pose |
[in] | tcurr | translation for current camera pose |
[in] | tranc_dist | tsdf truncation distance |
[in] | volume | tsdf volume to be updated |
[in] | buffer | cyclical buffer structure |
[out] | depthScaled | Buffer for scaled depth along ray |
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)
[in] | depth_raw | Kinect depth image |
[in] | intr | camera intrinsics |
[in] | volume_size | size of volume in mm |
[in] | Rcurr_inv | inverse rotation for current camera pose |
[in] | tcurr | translation for current camera pose |
[in] | tranc_dist | tsdf truncation distance |
[in] | volume | tsdf volume to be updated |
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.
[in] | cloud | points cloud |
[in] | normals | normals cloud |
[out] | output | array of PointNomals. |
__device__ __forceinline__ float pcl::device::kinfuLS::norm | ( | const float3 & | v | ) |
__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().
__device__ __forceinline__ float3 pcl::device::kinfuLS::operator* | ( | const float3 & | v1, |
const float & | v | ||
) |
__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().
__device__ __forceinline__ float3& pcl::device::kinfuLS::operator*= | ( | float3 & | vec, |
const float & | v | ||
) |
__device__ __forceinline__ float3 pcl::device::kinfuLS::operator+ | ( | const float3 & | v1, |
const float3 & | v2 | ||
) |
__device__ __forceinline__ float3& pcl::device::kinfuLS::operator+= | ( | float3 & | vec, |
const float & | v | ||
) |
__device__ __forceinline__ float3 pcl::device::kinfuLS::operator- | ( | const float3 & | v1, |
const float3 & | v2 | ||
) |
__device__ __forceinline__ void pcl::device::kinfuLS::pack_tsdf | ( | float | tsdf, |
int | weight, | ||
short2 & | value | ||
) |
Definition at line 56 of file device.hpp.
References DIVISOR.
void pcl::device::kinfuLS::paint3DView | ( | const PtrStep< uchar3 > & | colors, |
PtrStepSz< uchar3 > | dst, | ||
float | colors_weight = 0.5f |
||
) |
Paints 3D view with color map.
[in] | colors | rgb color frame from OpenNI |
[out] | dst | output 3D view |
[in] | colors_weight | weight for colors |
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.
[in] | volume | tsdf volume |
[in] | cloud_gpu | contains the data to be pushed to the tsdf volume |
[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. |
Computes depth pyramid.
[in] | src | source |
[out] | dst | destination |
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.
[in] | intr | camera intrinsices |
[in] | Rcurr | current rotation |
[in] | tcurr | current translation |
[in] | tranc_dist | volume truncation distance |
[in] | volume_size | volume size in mm |
[in] | volume | tsdf volume |
[in] | buffer | cyclical buffer structure |
[out] | vmap | output vertex map |
[out] | nmap | output normals map |
Performs resize of vertex map to next pyramid level by averaging each four normals.
[in] | input | normal map |
[out] | output | vertex map |
Performs resize of vertex map to next pyramid level by averaging each four points.
[in] | input | vertext map |
[out] | output | resized vertex map |
__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.
__device__ __host__ __forceinline__ void pcl::device::kinfuLS::swap | ( | T & | a, |
T & | b | ||
) |
Definition at line 55 of file utils.hpp.
Referenced by computeRoots3().
|
inline |
synchronizes CUDA execution
Definition at line 411 of file internal.h.
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.
[in] | vmap_src | source vertex map |
[in] | nmap_src | source vertex map |
[in] | Rmat | Rotation mat |
[in] | tvec | translation |
[out] | vmap_dst | destination vertex map |
[out] | nmap_dst | destination vertex map |
void pcl::device::kinfuLS::truncateDepth | ( | DepthMap & | depth, |
float | max_distance | ||
) |
Performs depth truncation.
[out] | depth | depth map to truncation |
[in] | max_distance | truncation threshold, values that are higher than the threshold are reset to zero (means not measurement) |
void pcl::device::kinfuLS::unbindTextures | ( | ) |
Unbinds.
__device__ __forceinline__ float pcl::device::kinfuLS::unpack_tsdf | ( | short2 | value | ) |
Definition at line 71 of file device.hpp.
References DIVISOR.
__device__ __forceinline__ void pcl::device::kinfuLS::unpack_tsdf | ( | short2 | value, |
float & | tsdf, | ||
int & | weight | ||
) |
Definition at line 64 of file device.hpp.
References DIVISOR.
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.
[in] | intr | Depth camera intrionsics structure |
[in] | tranc_dist | tsdf truncation distance |
[in] | R_inv | Inverse camera rotation |
[in] | t | camera translation |
[in] | vmap | Raycasted vertex map |
[in] | colors | RGB colors for current frame |
[in] | volume_size | volume size in meters |
[in] | color_volume | color volume to be integrated |
[in] | max_weight | max weight for running color average. Zero means not average, one means average with prev value, etc. |
|
inline |
|
constexpr |
|
constexpr |
Definition at line 62 of file device.h.
Referenced by pack_tsdf(), and unpack_tsdf().
|
constexpr |
|
constexpr |
|
constexpr |
|
constexpr |
|
constexpr |
|
constexpr |
|
constexpr |