internal.hpp
Go to the documentation of this file.
1 #pragma once
2 
4 #include <kfusion/tsdf_buffer.h>
5 #include "safe_call.hpp"
6 
7 //#define USE_DEPTH
8 
9 namespace kfusion
10 {
11  namespace device
12  {
13  typedef float4 Normal;
14  typedef float4 Point;
15 
16  typedef unsigned short ushort;
17  typedef unsigned char uchar;
18 
24 
25  typedef int3 Vec3i;
26  typedef float3 Vec3f;
27  struct Mat3f { float3 data[3]; };
28  struct Aff3f { Mat3f R; Vec3f t; };
29 
30  struct TsdfVolume
31  {
32  public:
33  typedef ushort2 elem_type;
34 
35  elem_type *const data;
36  const int3 dims;
37  const float3 voxel_size;
38  const float trunc_dist;
39  const int max_weight;
40 
41  TsdfVolume(elem_type* data, int3 dims, float3 voxel_size, float trunc_dist, int max_weight);
42  //TsdfVolume(const TsdfVolume&);
43 
44  __kf_device__ elem_type* operator()(int x, int y, int z);
45  __kf_device__ const elem_type* operator() (int x, int y, int z) const ;
46  __kf_device__ elem_type* beg(int x, int y) const;
47  __kf_device__ elem_type* zstep(elem_type *const ptr) const;
48  __kf_device__ elem_type* multzstep(int mult, elem_type *const ptr) const;
49 
50 
51  private:
53  };
54 
55  struct Projector
56  {
57  float2 f, c;
59  Projector(float fx, float fy, float cx, float cy);
60  __kf_device__ float2 operator()(const float3& p) const;
61  };
62 
63  struct Reprojector
64  {
66  Reprojector(float fx, float fy, float cx, float cy);
67  float2 finv, c;
68  __kf_device__ float3 operator()(int x, int y, float z) const;
69  };
70 
72  {
73  struct Policy;
75  {
76  float* data;
79  };
80 
81  float min_cosine;
82  float dist2_thres;
83 
85 
86  float rows, cols;
87  float2 f, c, finv;
88 
92 
93  ComputeIcpHelper(float dist_thres, float angle_thres);
94  void setLevelIntr(int level_index, float fx, float fy, float cx, float cy);
95 
96  void operator()(const Depth& dprev, const Normals& nprev, DeviceArray2D<float>& buffer, float* data, cudaStream_t stream);
97  void operator()(const Points& vprev, const Normals& nprev, DeviceArray2D<float>& buffer, float* data, cudaStream_t stream);
98 
99  static void allocate_buffer(DeviceArray2D<float>& buffer, int partials_count = -1);
100 
101  //private:
102  __kf_device__ int find_coresp(int x, int y, float3& n, float3& d, float3& s) const;
103  __kf_device__ void partial_reduce(const float row[7], PtrStep<float>& partial_buffer) const;
104  __kf_device__ float2 proj(const float3& p) const;
105  __kf_device__ float3 reproj(float x, float y, float z) const;
106  };
107 
108  //tsdf volume functions
109  void clear_volume(TsdfVolume volume);
110  void clearTSDFSlice (const TsdfVolume& volume, const kfusion::tsdf_buffer* buffer, const Vec3i offset);
111  void integrate(const Dists& depth, TsdfVolume& volume, tsdf_buffer& buffer, const Aff3f& aff, const Projector& proj);
112 
113  void raycast(const TsdfVolume& volume, tsdf_buffer& buffer, const Aff3f& aff, const Mat3f& Rinv,
114  const Reprojector& reproj, Depth& depth, Normals& normals, float step_factor, float delta_factor);
115 
116  void raycast(const TsdfVolume& volume, tsdf_buffer& buffer, const Aff3f& aff, const Mat3f& Rinv,
117  const Reprojector& reproj, Points& points, Normals& normals, float step_factor, float delta_factor);
118 
119  __kf_device__ ushort2 pack_tsdf(float tsdf, int weight);
120  __kf_device__ float unpack_tsdf(ushort2 value, int& weight);
121  __kf_device__ float unpack_tsdf(ushort2 value);
122 
123 
124  //image proc functions
125  void compute_dists(const Depth& depth, Dists dists, float2 f, float2 c);
126 
127  void truncateDepth(Depth& depth, float max_dist /*meters*/);
128  void bilateralFilter(const Depth& src, Depth& dst, int kernel_size, float sigma_spatial, float sigma_depth);
129  void depthPyr(const Depth& source, Depth& pyramid, float sigma_depth);
130 
131  void resizeDepthNormals(const Depth& depth, const Normals& normals, Depth& depth_out, Normals& normals_out);
132  void resizePointsNormals(const Points& points, const Normals& normals, Points& points_out, Normals& normals_out);
133 
134  void computeNormalsAndMaskDepth(const Reprojector& reproj, Depth& depth, Normals& normals);
135  void computePointNormals(const Reprojector& reproj, const Depth& depth, Points& points, Normals& normals);
136 
137  void renderImage(const Depth& depth, const Normals& normals, const Reprojector& reproj, const Vec3f& light_pose, Image& image);
138  void renderImage(const Points& points, const Normals& normals, const Reprojector& reproj, const Vec3f& light_pose, Image& image);
139  void renderTangentColors(const Normals& normals, Image& image);
140 
141 
142  //exctraction functionality
143  size_t extractSliceAsCloud (const TsdfVolume& volume, const kfusion::tsdf_buffer* buffer,
144  const Vec3i minBounds, const Vec3i maxBounds, const Vec3i globalShift
145  , const Aff3f& aff, PtrSz<Point> output);
146  size_t extractCloud(const TsdfVolume& volume, const tsdf_buffer& buffer, const Aff3f& aff, PtrSz<Point> output);
147  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);
148 
149 
150  //push
151  //void pushCloudAsSliceGPU (const TsdfVolume& volume, DeviceArray<float3> cloud_gpu, const tsdf_buffer* buffer);
152 
153  struct float8 { float x, y, z, w, c1, c2, c3, c4; };
154  struct float12 { float x, y, z, w, normal_x, normal_y, normal_z, n4, c1, c2, c3, c4; };
155  void mergePointNormal(const DeviceArray<Point>& cloud, const DeviceArray<float8>& normals, const DeviceArray<float12>& output);
156  }
157 }
kfusion::device::float12::y
float y
Definition: internal.hpp:154
kfusion::device::renderTangentColors
void renderTangentColors(const Normals &normals, Image &image)
kfusion::device::float12::c2
float c2
Definition: internal.hpp:154
kfusion::device::depthPyr
void depthPyr(const Depth &source, Depth &pyramid, float sigma_depth)
kfusion::device::float12::z
float z
Definition: internal.hpp:154
kfusion::device::resizePointsNormals
void resizePointsNormals(const Points &points, const Normals &normals, Points &points_out, Normals &normals_out)
kfusion::device::Points
DeviceArray2D< Point > Points
Definition: internal.hpp:22
kfusion::device::TsdfVolume::TsdfVolume
TsdfVolume(elem_type *data, int3 dims, float3 voxel_size, float trunc_dist, int max_weight)
TsdfVolume host implementation.
Definition: precomp.cpp:29
kfusion::device::Projector::operator()
__kf_device__ float2 operator()(const float3 &p) const
Projector.
Definition: device.hpp:35
kfusion::device::float8::c2
float c2
Definition: internal.hpp:153
kfusion::device::truncateDepth
void truncateDepth(Depth &depth, float max_dist)
kfusion::device::float12::normal_x
float normal_x
Definition: internal.hpp:154
kfusion::device::TsdfVolume::data
elem_type *const data
Definition: internal.hpp:35
kfusion::device::float8::c3
float c3
Definition: internal.hpp:153
kfusion::device::Depth
DeviceArray2D< ushort > Depth
Definition: internal.hpp:20
kfusion::device::float12::c4
float c4
Definition: internal.hpp:154
kfusion::device::Projector::f
float2 f
Definition: internal.hpp:57
kfusion::device::ComputeIcpHelper::find_coresp
__kf_device__ int find_coresp(int x, int y, float3 &n, float3 &d, float3 &s) const
kfusion::device::uchar
unsigned char uchar
Definition: internal.hpp:17
kfusion::device::ComputeIcpHelper::allocate_buffer
static void allocate_buffer(DeviceArray2D< float > &buffer, int partials_count=-1)
kfusion::device::ComputeIcpHelper::operator()
void operator()(const Depth &dprev, const Normals &nprev, DeviceArray2D< float > &buffer, float *data, cudaStream_t stream)
kfusion::device::float12::x
float x
Definition: internal.hpp:154
kfusion::device::Mat3f::data
float3 data[3]
Definition: internal.hpp:27
kfusion::device::float12::c3
float c3
Definition: internal.hpp:154
p
SharedPointer p
Definition: ConvertShared.hpp:42
kfusion::device::Aff3f::t
Vec3f t
Definition: internal.hpp:28
kfusion::device::Reprojector
Definition: internal.hpp:63
kfusion::device::TsdfVolume::beg
__kf_device__ elem_type * beg(int x, int y) const
Definition: device.hpp:24
kfusion::device::ComputeIcpHelper::PageLockHelper::~PageLockHelper
~PageLockHelper()
kfusion::device::float12::normal_y
float normal_y
Definition: internal.hpp:154
kfusion::device::float8::y
float y
Definition: internal.hpp:153
kfusion::device::Image
DeviceArray2D< uchar4 > Image
Definition: internal.hpp:23
kfusion::device::resizeDepthNormals
void resizeDepthNormals(const Depth &depth, const Normals &normals, Depth &depth_out, Normals &normals_out)
kfusion::device::Vec3f
float3 Vec3f
Definition: internal.hpp:26
kfusion::device::ComputeIcpHelper::rows
float rows
Definition: internal.hpp:86
kfusion::device::unpack_tsdf
__kf_device__ float unpack_tsdf(ushort2 value, int &weight)
Definition: device.hpp:59
kfusion::device::TsdfVolume::multzstep
__kf_device__ elem_type * multzstep(int mult, elem_type *const ptr) const
Definition: device.hpp:30
kfusion::device::TsdfVolume::zstep
__kf_device__ elem_type * zstep(elem_type *const ptr) const
Definition: device.hpp:27
kfusion::device::computeNormalsAndMaskDepth
void computeNormalsAndMaskDepth(const Reprojector &reproj, Depth &depth, Normals &normals)
kfusion::device::Reprojector::operator()
__kf_device__ float3 operator()(int x, int y, float z) const
Reprojector.
Definition: device.hpp:46
kfusion::device::Vec3i
int3 Vec3i
Definition: internal.hpp:25
kfusion::device::pack_tsdf
__kf_device__ ushort2 pack_tsdf(float tsdf, int weight)
packing/unpacking tsdf volume element
Definition: device.hpp:56
kfusion::device::float8::x
float x
Definition: internal.hpp:153
kfusion::device::float8::z
float z
Definition: internal.hpp:153
kfusion::device::Normal
float4 Normal
Definition: internal.hpp:13
kfusion::device::TsdfVolume::elem_type
ushort2 elem_type
Definition: internal.hpp:33
kfusion::device::ComputeIcpHelper::partial_reduce
__kf_device__ void partial_reduce(const float row[7], PtrStep< float > &partial_buffer) const
kfusion::device::Projector::c
float2 c
Definition: internal.hpp:57
kfusion::device::Reprojector::Reprojector
Reprojector()
Definition: internal.hpp:65
kfusion::device::Projector::Projector
Projector()
Definition: internal.hpp:58
kfusion::device::bilateralFilter
void bilateralFilter(const Depth &src, Depth &dst, int kernel_size, float sigma_spatial, float sigma_depth)
kfusion::device::ComputeIcpHelper::reproj
__kf_device__ float3 reproj(float x, float y, float z) const
kfusion
Utility.
Definition: capture.hpp:8
kfusion::cuda::PtrSz
Definition: kernel_containers.hpp:32
kfusion::device::ComputeIcpHelper::dist2_thres
float dist2_thres
Definition: internal.hpp:82
kfusion::device::ComputeIcpHelper::vcurr
PtrStep< Point > vcurr
Definition: internal.hpp:91
kfusion::device::Mat3f
Definition: internal.hpp:27
kfusion::device::float12::w
float w
Definition: internal.hpp:154
kfusion::device::Aff3f
Definition: internal.hpp:28
kfusion::device::float8::c1
float c1
Definition: internal.hpp:153
kfusion::device::Aff3f::R
Mat3f R
Definition: internal.hpp:28
kfusion::device::ComputeIcpHelper::f
float2 f
Definition: internal.hpp:87
kfusion::device::raycast
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)
kfusion::device::Normals
DeviceArray2D< Normal > Normals
Definition: internal.hpp:21
kfusion::cuda::DeviceArray
DeviceArray class
Definition: device_array.hpp:20
kfusion::device::TsdfVolume::operator()
__kf_device__ elem_type * operator()(int x, int y, int z)
TsdfVolume.
Definition: device.hpp:18
kfusion::device::extractCloud
size_t extractCloud(const TsdfVolume &volume, const tsdf_buffer &buffer, const Aff3f &aff, PtrSz< Point > output)
kfusion::device::extractNormals
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)
kfusion::device::float8::c4
float c4
Definition: internal.hpp:153
kfusion::device::Reprojector::c
float2 c
Definition: internal.hpp:67
kfusion::device::ComputeIcpHelper::ComputeIcpHelper
ComputeIcpHelper(float dist_thres, float angle_thres)
ComputeIcpHelper.
Definition: projective_icp.cpp:11
kfusion::device::ComputeIcpHelper::min_cosine
float min_cosine
Definition: internal.hpp:81
kfusion::device::TsdfVolume::trunc_dist
const float trunc_dist
Definition: internal.hpp:38
kfusion::device::Projector
Definition: internal.hpp:55
kfusion::device::TsdfVolume::voxel_size
const float3 voxel_size
Definition: internal.hpp:37
kfusion::device::Point
float4 Point
Definition: internal.hpp:14
safe_call.hpp
kfusion::tsdf_buffer
Structure to handle buffer addresses.
Definition: tsdf_buffer.h:48
kfusion::device::TsdfVolume::dims
const int3 dims
Definition: internal.hpp:36
kfusion::device::ComputeIcpHelper::proj
__kf_device__ float2 proj(const float3 &p) const
kfusion::device::clearTSDFSlice
void clearTSDFSlice(const TsdfVolume &volume, const kfusion::tsdf_buffer *buffer, const Vec3i offset)
kfusion::device::ComputeIcpHelper::finv
float2 finv
Definition: internal.hpp:87
__kf_device__
#define __kf_device__
Definition: kernel_containers.hpp:8
kfusion::device::ComputeIcpHelper::cols
float cols
Definition: internal.hpp:86
kfusion::device::Dists
PtrStepSz< ushort > Dists
Definition: internal.hpp:19
device_array.hpp
kfusion::device::compute_dists
void compute_dists(const Depth &depth, Dists dists, float2 f, float2 c)
kfusion::device::Reprojector::finv
float2 finv
Definition: internal.hpp:67
kfusion::device::float12::n4
float n4
Definition: internal.hpp:154
kfusion::device::float12::c1
float c1
Definition: internal.hpp:154
kfusion::device::ComputeIcpHelper::PageLockHelper
Definition: internal.hpp:74
kfusion::device::float8::w
float w
Definition: internal.hpp:153
kfusion::device::computePointNormals
void computePointNormals(const Reprojector &reproj, const Depth &depth, Points &points, Normals &normals)
kfusion::device::ComputeIcpHelper
Definition: internal.hpp:71
kfusion::device::ComputeIcpHelper::ncurr
PtrStep< Normal > ncurr
Definition: internal.hpp:90
kfusion::device::ushort
unsigned short ushort
Definition: internal.hpp:16
kfusion::device::ComputeIcpHelper::PageLockHelper::data
float * data
Definition: internal.hpp:76
tsdf_buffer.h
kfusion::device::float12
Definition: internal.hpp:154
kfusion::device::float8
Definition: internal.hpp:153
kfusion::cuda::PtrStepSz
Definition: kernel_containers.hpp:55
kfusion::device::extractSliceAsCloud
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)
kfusion::device::TsdfVolume
Definition: internal.hpp:30
kfusion::device::integrate
void integrate(const Dists &depth, TsdfVolume &volume, tsdf_buffer &buffer, const Aff3f &aff, const Projector &proj)
kfusion::device::TsdfVolume::operator=
TsdfVolume & operator=(const TsdfVolume &)
kfusion::device::ComputeIcpHelper::c
float2 c
Definition: internal.hpp:87
kfusion::cuda::DeviceArray2D
DeviceArray2D class
Definition: device_array.hpp:117
kfusion::device::mergePointNormal
void mergePointNormal(const DeviceArray< Point > &cloud, const DeviceArray< float8 > &normals, const DeviceArray< float12 > &output)
kfusion::device::ComputeIcpHelper::PageLockHelper::PageLockHelper
PageLockHelper()
kfusion::device::clear_volume
void clear_volume(TsdfVolume volume)
kfusion::device::float12::normal_z
float normal_z
Definition: internal.hpp:154
kfusion::device::ComputeIcpHelper::setLevelIntr
void setLevelIntr(int level_index, float fx, float fy, float cx, float cy)
Definition: projective_icp.cpp:17
kfusion::device::renderImage
void renderImage(const Depth &depth, const Normals &normals, const Reprojector &reproj, const Vec3f &light_pose, Image &image)
kfusion::device::ComputeIcpHelper::aff
Aff3f aff
Definition: internal.hpp:84
kfusion::device::ComputeIcpHelper::dcurr
PtrStep< ushort > dcurr
Definition: internal.hpp:89
kfusion::device::TsdfVolume::max_weight
const int max_weight
Definition: internal.hpp:39
kfusion::cuda::PtrStep
Definition: kernel_containers.hpp:40


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:23