Classes | Typedefs | Functions
kfusion::device Namespace Reference

Classes

struct  Aff3f
 
struct  Block
 
struct  ComputeIcpHelper
 
struct  Eigen33
 
struct  Emulation
 
struct  float12
 
struct  float8
 
struct  gmem
 
struct  Mat3f
 
struct  numeric_limits
 
struct  numeric_limits< float >
 
struct  numeric_limits< unsigned short >
 
struct  plus
 
struct  Projector
 
struct  Reprojector
 
struct  TsdfVolume
 
struct  Warp
 

Typedefs

typedef DeviceArray2D< ushortDepth
 
typedef PtrStepSz< ushortDists
 
typedef DeviceArray2D< uchar4 > Image
 
typedef float4 Normal
 
typedef DeviceArray2D< NormalNormals
 
typedef float4 Point
 
typedef DeviceArray2D< PointPoints
 
typedef unsigned char uchar
 
typedef unsigned short ushort
 
typedef float3 Vec3f
 
typedef int3 Vec3i
 

Functions

void bilateralFilter (const Depth &src, Depth &dst, int kernel_size, float sigma_spatial, float sigma_depth)
 
void clear_volume (TsdfVolume volume)
 
void clearTSDFSlice (const TsdfVolume &volume, const kfusion::tsdf_buffer *buffer, const Vec3i offset)
 
void compute_dists (const Depth &depth, Dists dists, float2 f, float2 c)
 
void computeNormalsAndMaskDepth (const Reprojector &reproj, Depth &depth, Normals &normals)
 
void computePointNormals (const Reprojector &reproj, const Depth &depth, Points &points, Normals &normals)
 
__kf_device__ void computeRoots2 (const float &b, const float &c, float3 &roots)
 
__kf_device__ void computeRoots3 (float c0, float c1, float c2, float3 &roots)
 
__kf_hdevice__ float3 cross (const float3 &v1, const float3 &v2)
 
void depthPyr (const Depth &source, Depth &pyramid, float sigma_depth)
 
__kf_device__ float dot (const float3 &v1, const float3 &v2)
 
size_t extractCloud (const TsdfVolume &volume, const tsdf_buffer &buffer, const Aff3f &aff, PtrSz< Point > output)
 
void extractNormals (const TsdfVolume &volume, const tsdf_buffer &buffer, const PtrSz< Point > &points, const Aff3f &aff, const Mat3f &Rinv, float gradient_delta_factor, float4 *output)
 
size_t extractSliceAsCloud (const TsdfVolume &volume, const kfusion::tsdf_buffer *buffer, const Vec3i minBounds, const Vec3i maxBounds, const Vec3i globalShift, const Aff3f &aff, PtrSz< Point > output)
 
void integrate (const Dists &depth, TsdfVolume &volume, tsdf_buffer &buffer, const Aff3f &aff, const Projector &proj)
 
void mergePointNormal (const DeviceArray< Point > &cloud, const DeviceArray< float8 > &normals, const DeviceArray< float12 > &output)
 
__kf_device__ float norm (const float3 &v)
 
__kf_device__ float norm_sqr (const float3 &v)
 
__kf_device__ float3 normalized (const float3 &v)
 
__kf_device__ Vec3f operator* (const Aff3f &a, const Vec3f &v)
 
__kf_hdevice__ float3 operator* (const float &v, const float3 &v1)
 
__kf_hdevice__ float3 operator* (const float3 &v1, const float &v)
 
__kf_device__ float3 operator* (const float3 &v1, const float3 &v2)
 
__kf_hdevice__ float3 operator* (const float3 &v1, const int3 &v2)
 
__kf_device__ Vec3f operator* (const Mat3f &m, const Vec3f &v)
 
__kf_device__ float3 & operator*= (float3 &vec, const float &v)
 
__kf_device__ float3 operator+ (const float3 &v1, const float3 &v2)
 
__kf_device__ float3 & operator+= (float3 &v1, const float3 &v2)
 
__kf_device__ float3 & operator+= (float3 &vec, const float &v)
 
__kf_device__ float3 operator- (const float3 &v1, const float3 &v2)
 
__kf_hdevice__ float3 operator/ (const float &v, const float3 &vec)
 
__kf_device__ float3 operator/ (const float3 &v1, const float3 &v2)
 
__kf_device__ ushort2 pack_tsdf (float tsdf, int weight)
 packing/unpacking tsdf volume element More...
 
void raycast (const TsdfVolume &volume, tsdf_buffer &buffer, const Aff3f &aff, const Mat3f &Rinv, const Reprojector &reproj, Depth &depth, Normals &normals, float step_factor, float delta_factor)
 
void raycast (const TsdfVolume &volume, tsdf_buffer &buffer, const Aff3f &aff, const Mat3f &Rinv, const Reprojector &reproj, Points &points, Normals &normals, float step_factor, float delta_factor)
 
void renderImage (const Depth &depth, const Normals &normals, const Reprojector &reproj, const Vec3f &light_pose, Image &image)
 
void renderImage (const Points &points, const Normals &normals, const Reprojector &reproj, const Vec3f &light_pose, Image &image)
 
void renderTangentColors (const Normals &normals, Image &image)
 
void resizeDepthNormals (const Depth &depth, const Normals &normals, Depth &depth_out, Normals &normals_out)
 
void resizePointsNormals (const Points &points, const Normals &normals, Points &points_out, Normals &normals_out)
 
template<class T >
__kf_hdevice__ void swap (T &a, T &b)
 
__kf_device__ Vec3f tr (const float4 &v)
 
void truncateDepth (Depth &depth, float max_dist)
 
__kf_device__ float unpack_tsdf (ushort2 value)
 
__kf_device__ float unpack_tsdf (ushort2 value, int &weight)
 

Typedef Documentation

◆ Depth

Definition at line 20 of file internal.hpp.

◆ Dists

Definition at line 19 of file internal.hpp.

◆ Image

Definition at line 23 of file internal.hpp.

◆ Normal

typedef float4 kfusion::device::Normal

Definition at line 13 of file internal.hpp.

◆ Normals

Definition at line 21 of file internal.hpp.

◆ Point

typedef float4 kfusion::device::Point

Definition at line 14 of file internal.hpp.

◆ Points

Definition at line 22 of file internal.hpp.

◆ uchar

typedef unsigned char kfusion::device::uchar

Definition at line 17 of file internal.hpp.

◆ ushort

typedef unsigned short kfusion::device::ushort

Definition at line 16 of file internal.hpp.

◆ Vec3f

typedef float3 kfusion::device::Vec3f

Definition at line 26 of file internal.hpp.

◆ Vec3i

typedef int3 kfusion::device::Vec3i

Definition at line 25 of file internal.hpp.

Function Documentation

◆ bilateralFilter()

void kfusion::device::bilateralFilter ( const Depth src,
Depth dst,
int  kernel_size,
float  sigma_spatial,
float  sigma_depth 
)

◆ clear_volume()

void kfusion::device::clear_volume ( TsdfVolume  volume)

◆ clearTSDFSlice()

void kfusion::device::clearTSDFSlice ( const TsdfVolume volume,
const kfusion::tsdf_buffer buffer,
const Vec3i  offset 
)

◆ compute_dists()

void kfusion::device::compute_dists ( const Depth depth,
Dists  dists,
float2  f,
float2  c 
)

◆ computeNormalsAndMaskDepth()

void kfusion::device::computeNormalsAndMaskDepth ( const Reprojector reproj,
Depth depth,
Normals normals 
)

◆ computePointNormals()

void kfusion::device::computePointNormals ( const Reprojector reproj,
const Depth depth,
Points points,
Normals normals 
)

◆ computeRoots2()

__kf_device__ void kfusion::device::computeRoots2 ( const float &  b,
const float &  c,
float3 &  roots 
)

Definition at line 107 of file temp_utils.hpp.

◆ computeRoots3()

__kf_device__ void kfusion::device::computeRoots3 ( float  c0,
float  c1,
float  c2,
float3 &  roots 
)

Definition at line 120 of file temp_utils.hpp.

◆ cross()

__kf_hdevice__ float3 kfusion::device::cross ( const float3 &  v1,
const float3 &  v2 
)

Definition at line 102 of file temp_utils.hpp.

◆ depthPyr()

void kfusion::device::depthPyr ( const Depth source,
Depth pyramid,
float  sigma_depth 
)

◆ dot()

__kf_device__ float kfusion::device::dot ( const float3 &  v1,
const float3 &  v2 
)

Definition at line 27 of file temp_utils.hpp.

◆ extractCloud()

size_t kfusion::device::extractCloud ( const TsdfVolume volume,
const tsdf_buffer buffer,
const Aff3f aff,
PtrSz< Point output 
)

◆ extractNormals()

void kfusion::device::extractNormals ( const TsdfVolume volume,
const tsdf_buffer buffer,
const PtrSz< Point > &  points,
const Aff3f aff,
const Mat3f Rinv,
float  gradient_delta_factor,
float4 *  output 
)

◆ extractSliceAsCloud()

size_t kfusion::device::extractSliceAsCloud ( const TsdfVolume volume,
const kfusion::tsdf_buffer buffer,
const Vec3i  minBounds,
const Vec3i  maxBounds,
const Vec3i  globalShift,
const Aff3f aff,
PtrSz< Point output 
)

◆ integrate()

void kfusion::device::integrate ( const Dists depth,
TsdfVolume volume,
tsdf_buffer buffer,
const Aff3f aff,
const Projector proj 
)

◆ mergePointNormal()

void kfusion::device::mergePointNormal ( const DeviceArray< Point > &  cloud,
const DeviceArray< float8 > &  normals,
const DeviceArray< float12 > &  output 
)

◆ norm()

__kf_device__ float kfusion::device::norm ( const float3 &  v)

Definition at line 87 of file temp_utils.hpp.

◆ norm_sqr()

__kf_device__ float kfusion::device::norm_sqr ( const float3 &  v)

Definition at line 92 of file temp_utils.hpp.

◆ normalized()

__kf_device__ float3 kfusion::device::normalized ( const float3 &  v)

Definition at line 97 of file temp_utils.hpp.

◆ operator*() [1/6]

__kf_device__ Vec3f kfusion::device::operator* ( const Aff3f a,
const Vec3f v 
)

Definition at line 77 of file device.hpp.

◆ operator*() [2/6]

__kf_hdevice__ float3 kfusion::device::operator* ( const float &  v,
const float3 &  v1 
)

Definition at line 82 of file temp_utils.hpp.

◆ operator*() [3/6]

__kf_hdevice__ float3 kfusion::device::operator* ( const float3 &  v1,
const float &  v 
)

Definition at line 77 of file temp_utils.hpp.

◆ operator*() [4/6]

__kf_device__ float3 kfusion::device::operator* ( const float3 &  v1,
const float3 &  v2 
)

Definition at line 47 of file temp_utils.hpp.

◆ operator*() [5/6]

__kf_hdevice__ float3 kfusion::device::operator* ( const float3 &  v1,
const int3 &  v2 
)

Definition at line 52 of file temp_utils.hpp.

◆ operator*() [6/6]

__kf_device__ Vec3f kfusion::device::operator* ( const Mat3f m,
const Vec3f v 
)

Definition at line 74 of file device.hpp.

◆ operator*=()

__kf_device__ float3& kfusion::device::operator*= ( float3 &  vec,
const float &  v 
)

Definition at line 67 of file temp_utils.hpp.

◆ operator+()

__kf_device__ float3 kfusion::device::operator+ ( const float3 &  v1,
const float3 &  v2 
)

Definition at line 42 of file temp_utils.hpp.

◆ operator+=() [1/2]

__kf_device__ float3& kfusion::device::operator+= ( float3 &  v1,
const float3 &  v2 
)

Definition at line 37 of file temp_utils.hpp.

◆ operator+=() [2/2]

__kf_device__ float3& kfusion::device::operator+= ( float3 &  vec,
const float &  v 
)

Definition at line 32 of file temp_utils.hpp.

◆ operator-()

__kf_device__ float3 kfusion::device::operator- ( const float3 &  v1,
const float3 &  v2 
)

Definition at line 72 of file temp_utils.hpp.

◆ operator/() [1/2]

__kf_hdevice__ float3 kfusion::device::operator/ ( const float &  v,
const float3 &  vec 
)

Definition at line 62 of file temp_utils.hpp.

◆ operator/() [2/2]

__kf_device__ float3 kfusion::device::operator/ ( const float3 &  v1,
const float3 &  v2 
)

Definition at line 57 of file temp_utils.hpp.

◆ pack_tsdf()

__kf_device__ ushort2 kfusion::device::pack_tsdf ( float  tsdf,
int  weight 
)

packing/unpacking tsdf volume element

Definition at line 56 of file device.hpp.

◆ raycast() [1/2]

void kfusion::device::raycast ( const TsdfVolume volume,
tsdf_buffer buffer,
const Aff3f aff,
const Mat3f Rinv,
const Reprojector reproj,
Depth depth,
Normals normals,
float  step_factor,
float  delta_factor 
)

◆ raycast() [2/2]

void kfusion::device::raycast ( const TsdfVolume volume,
tsdf_buffer buffer,
const Aff3f aff,
const Mat3f Rinv,
const Reprojector reproj,
Points points,
Normals normals,
float  step_factor,
float  delta_factor 
)

◆ renderImage() [1/2]

void kfusion::device::renderImage ( const Depth depth,
const Normals normals,
const Reprojector reproj,
const Vec3f light_pose,
Image image 
)

◆ renderImage() [2/2]

void kfusion::device::renderImage ( const Points points,
const Normals normals,
const Reprojector reproj,
const Vec3f light_pose,
Image image 
)

◆ renderTangentColors()

void kfusion::device::renderTangentColors ( const Normals normals,
Image image 
)

◆ resizeDepthNormals()

void kfusion::device::resizeDepthNormals ( const Depth depth,
const Normals normals,
Depth depth_out,
Normals normals_out 
)

◆ resizePointsNormals()

void kfusion::device::resizePointsNormals ( const Points points,
const Normals normals,
Points points_out,
Normals normals_out 
)

◆ swap()

template<class T >
__kf_hdevice__ void kfusion::device::swap ( T &  a,
T &  b 
)

Definition at line 10 of file temp_utils.hpp.

◆ tr()

__kf_device__ Vec3f kfusion::device::tr ( const float4 &  v)

Definition at line 79 of file device.hpp.

◆ truncateDepth()

void kfusion::device::truncateDepth ( Depth depth,
float  max_dist 
)

◆ unpack_tsdf() [1/2]

__kf_device__ float kfusion::device::unpack_tsdf ( ushort2  value)

Definition at line 64 of file device.hpp.

◆ unpack_tsdf() [2/2]

__kf_device__ float kfusion::device::unpack_tsdf ( ushort2  value,
int &  weight 
)

Definition at line 59 of file device.hpp.



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