tsdf_volume.cpp
Go to the documentation of this file.
1 #include <kfusion/precomp.hpp>
2 
3 using namespace kfusion;
4 using namespace kfusion::cuda;
5 
8 
10 { throw "Not implemented"; }
11 
13 { throw "Not implemented"; }
14 
17 
18 kfusion::cuda::TsdfVolume::TsdfVolume(const Vec3i& dims) : data_(), trunc_dist_(0.03f), max_weight_(128), dims_(dims),
19  size_(Vec3f::all(3.f)), pose_(Affine3f::Identity()), gradient_delta_factor_(0.75f), raycast_step_factor_(0.75f)
20 { create(dims_); }
21 
23 
25 {
26  dims_ = dims;
27  int voxels_number = dims_[0] * dims_[1] * dims_[2];
28  data_.create(voxels_number * sizeof(int));
29  setTruncDist(trunc_dist_);
30  clear();
31 }
32 
34 { return dims_; }
35 
37 {
38  return Vec3f(size_[0]/dims_[0], size_[1]/dims_[1], size_[2]/dims_[2]);
39 }
40 
41 const CudaData kfusion::cuda::TsdfVolume::data() const { return data_; }
42 CudaData kfusion::cuda::TsdfVolume::data() { return data_; }
43 Vec3f kfusion::cuda::TsdfVolume::getSize() const { return size_; }
44 
46 { size_ = size; setTruncDist(trunc_dist_); }
47 
48 float kfusion::cuda::TsdfVolume::getTruncDist() const { return trunc_dist_; }
49 
51 {
52  Vec3f vsz = getVoxelSize();
53  float max_coeff = std::max<float>(std::max<float>(vsz[0], vsz[1]), vsz[2]);
54  trunc_dist_ = std::max (distance, 2.1f * max_coeff);
55 }
56 
57 ushort2* kfusion::cuda::TsdfVolume::getCoord(int x, int y, int z, int dim_x, int dim_y)
58 {
59  return data_.ptr<ushort2>() + x + y*dim_x + z*dim_y*dim_x;
60 }
61 
62 int kfusion::cuda::TsdfVolume::getMaxWeight() const { return max_weight_; }
63 void kfusion::cuda::TsdfVolume::setMaxWeight(int weight) { max_weight_ = weight; }
65 void kfusion::cuda::TsdfVolume::setPose(const Affine3f& pose) { pose_ = pose; }
66 float kfusion::cuda::TsdfVolume::getRaycastStepFactor() const { return raycast_step_factor_; }
67 void kfusion::cuda::TsdfVolume::setRaycastStepFactor(float factor) { raycast_step_factor_ = factor; }
68 float kfusion::cuda::TsdfVolume::getGradientDeltaFactor() const { return gradient_delta_factor_; }
69 void kfusion::cuda::TsdfVolume::setGradientDeltaFactor(float factor) { gradient_delta_factor_ = factor; }
70 void kfusion::cuda::TsdfVolume::swap(CudaData& data) { data_.swap(data); }
71 void kfusion::cuda::TsdfVolume::applyAffine(const Affine3f& affine) { pose_ = affine * pose_; }
72 
74 {
75  device::Vec3i dims = device_cast<device::Vec3i>(dims_);
76  device::Vec3f vsz = device_cast<device::Vec3f>(getVoxelSize());
77 
78  device::TsdfVolume volume(data_.ptr<ushort2>(), dims, vsz, trunc_dist_, max_weight_);
79  device::clear_volume(volume);
80 }
81 
82 void kfusion::cuda::TsdfVolume::clearSlice(const kfusion::tsdf_buffer* buffer, const Vec3i offset) const
83 {
84  device::Vec3i dims = device_cast<device::Vec3i>(dims_);
85  device::Vec3f vsz = device_cast<device::Vec3f>(getVoxelSize());
86 
87  device::Vec3i offset_c;
88  offset_c.x = offset[0];
89  offset_c.y = offset[1];
90  offset_c.z = offset[2];
91 
92  device::TsdfVolume volume((ushort2*)data_.ptr<ushort2>(), dims, vsz, trunc_dist_, max_weight_);
93  device::clearTSDFSlice(volume, buffer, offset_c);
94 }
95 
96 void kfusion::cuda::TsdfVolume::integrate(const Dists& dists, tsdf_buffer& buffer, const Affine3f& camera_pose, const Intr& intr)
97 {
98  Affine3f vol2cam = camera_pose.inv() * pose_;
99 
100  device::Projector proj(intr.fx, intr.fy, intr.cx, intr.cy);
101 
102  device::Vec3i dims = device_cast<device::Vec3i>(dims_);
103  device::Vec3f vsz = device_cast<device::Vec3f>(getVoxelSize());
104  device::Aff3f aff = device_cast<device::Aff3f>(vol2cam);
105 
106  device::TsdfVolume volume(data_.ptr<ushort2>(), dims, vsz, trunc_dist_, max_weight_);
107  device::integrate(dists, volume, buffer, aff, proj);
108 }
109 
110 void kfusion::cuda::TsdfVolume::raycast(const Affine3f& camera_pose, tsdf_buffer& buffer, const Intr& intr, Depth& depth, Normals& normals)
111 {
113 
114  Affine3f cam2vol = pose_.inv() * camera_pose;
115 
116  device::Aff3f aff = device_cast<device::Aff3f>(cam2vol);
117  device::Mat3f Rinv = device_cast<device::Mat3f>(cam2vol.rotation().inv(cv::DECOMP_SVD));
118 
119  device::Reprojector reproj(intr.fx, intr.fy, intr.cx, intr.cy);
120 
121  device::Vec3i dims = device_cast<device::Vec3i>(dims_);
122  device::Vec3f vsz = device_cast<device::Vec3f>(getVoxelSize());
123 
124  device::TsdfVolume volume(data_.ptr<ushort2>(), dims, vsz, trunc_dist_, max_weight_);
125  device::raycast(volume, buffer, aff, Rinv, reproj, depth, n, raycast_step_factor_, gradient_delta_factor_);
126 
127 }
128 
129 void kfusion::cuda::TsdfVolume::raycast(const Affine3f& camera_pose, tsdf_buffer& buffer, const Intr& intr, Cloud& points, Normals& normals)
130 {
131  device::Normals& n = (device::Normals&)normals;
132  device::Points& p = (device::Points&)points;
133 
134  Affine3f cam2vol = pose_.inv() * camera_pose;
135 
136  device::Aff3f aff = device_cast<device::Aff3f>(cam2vol);
137  device::Mat3f Rinv = device_cast<device::Mat3f>(cam2vol.rotation().inv(cv::DECOMP_SVD));
138 
139  device::Reprojector reproj(intr.fx, intr.fy, intr.cx, intr.cy);
140 
141  device::Vec3i dims = device_cast<device::Vec3i>(dims_);
142  device::Vec3f vsz = device_cast<device::Vec3f>(getVoxelSize());
143 
144  device::TsdfVolume volume(data_.ptr<ushort2>(), dims, vsz, trunc_dist_, max_weight_);
145  device::raycast(volume, buffer, aff, Rinv, reproj, p, n, raycast_step_factor_, gradient_delta_factor_);
146 }
147 
149 {
150  enum { DEFAULT_CLOUD_BUFFER_SIZE = 10 * 1000 * 1000 };
151 
152  if (cloud_buffer.empty ())
153  cloud_buffer.create (DEFAULT_CLOUD_BUFFER_SIZE);
154 
156 
157  device::Vec3i dims = device_cast<device::Vec3i>(dims_);
158  device::Vec3f vsz = device_cast<device::Vec3f>(getVoxelSize());
159  device::Aff3f aff = device_cast<device::Aff3f>(pose_);
160 
161  device::TsdfVolume volume((ushort2*)data_.ptr<ushort2>(), dims, vsz, trunc_dist_, max_weight_);
162  size_t size = extractCloud(volume, buffer, aff, b);
163 
164  return DeviceArray<Point>((Point*)cloud_buffer.ptr(), size);
165 }
166 
168 {
169  normals.create(cloud.size());
171 
172  device::Vec3i dims = device_cast<device::Vec3i>(dims_);
173  device::Vec3f vsz = device_cast<device::Vec3f>(getVoxelSize());
174  device::Aff3f aff = device_cast<device::Aff3f>(pose_);
175  device::Mat3f Rinv = device_cast<device::Mat3f>(pose_.rotation().inv(cv::DECOMP_SVD));
176 
177  device::TsdfVolume volume((ushort2*)data_.ptr<ushort2>(), dims, vsz, trunc_dist_, max_weight_);
178  device::extractNormals(volume, buffer, c, aff, Rinv, gradient_delta_factor_, (float4*)normals.ptr());
179 }
180 
182 
184 kfusion::cuda::TsdfVolume::fetchSliceAsCloud (DeviceArray<Point>& cloud_buffer, const kfusion::tsdf_buffer* buffer, const Vec3i minBounds, const Vec3i maxBounds, const Vec3i globalShift ) const
185 {
186 
187  enum { DEFAULT_CLOUD_BUFFER_SIZE = 10 * 1000 * 1000 };
188  if (cloud_buffer.empty ())
189  cloud_buffer.create (DEFAULT_CLOUD_BUFFER_SIZE);
190 
192 
193  device::Vec3i dims = device_cast<device::Vec3i>(dims_);
194  device::Vec3i deviceGlobalShift;
195  deviceGlobalShift.x = globalShift[0];
196  deviceGlobalShift.y = globalShift[1];
197  deviceGlobalShift.z = globalShift[2];
198 
199  device::Vec3i minBounds_c;
200  minBounds_c.x = minBounds[0];
201  minBounds_c.y = minBounds[1];
202  minBounds_c.z = minBounds[2];
203 
204  device::Vec3i maxBounds_c;
205  maxBounds_c.x = maxBounds[0];
206  maxBounds_c.y = maxBounds[1];
207  maxBounds_c.z = maxBounds[2];
208 
209  device::Vec3f vsz = device_cast<device::Vec3f>(getVoxelSize());
210  device::Aff3f aff = device_cast<device::Aff3f>(pose_);
211 
212  device::TsdfVolume volume((ushort2*)data_.ptr<ushort2>(), dims, vsz, trunc_dist_, max_weight_);
213 
214  size_t size = extractSliceAsCloud (volume, buffer, minBounds_c, maxBounds_c, deviceGlobalShift, aff, b);
215 
216  return DeviceArray<Point>((Point*)cloud_buffer.ptr(), size);
217 }
kfusion::cuda::TsdfVolume::clearSlice
void clearSlice(const kfusion::tsdf_buffer *buffer, const Vec3i offset) const
Definition: tsdf_volume.cpp:82
kfusion::cuda::TsdfVolume::dims_
Vec3i dims_
Definition: tsdf_volume.hpp:90
kfusion::cuda::DeviceArray::size
size_t size() const
Returns size in elements.
Definition: device_array.hpp:257
kfusion::Vec3f
cv::Vec3f Vec3f
Definition: types.hpp:16
kfusion::cuda::TsdfVolume::TsdfVolume
TsdfVolume(const cv::Vec3i &dims)
TsdfVolume.
Definition: tsdf_volume.cpp:18
kfusion::cuda::TsdfVolume::getTruncDist
float getTruncDist() const
Definition: tsdf_volume.cpp:48
kfusion::cuda::TsdfVolume::setTruncDist
void setTruncDist(float distance)
Definition: tsdf_volume.cpp:50
precomp.hpp
kfusion::cuda::TsdfVolume::getGradientDeltaFactor
float getGradientDeltaFactor() const
Definition: tsdf_volume.cpp:68
p
SharedPointer p
Definition: ConvertShared.hpp:42
kfusion::device::Reprojector
Definition: internal.hpp:63
kfusion::cuda::TsdfVolume::getDims
Vec3i getDims() const
Definition: tsdf_volume.cpp:33
kfusion::cuda::DeviceMemory
DeviceMemory class
Definition: device_memory.hpp:21
kfusion::Affine3f
cv::Affine3f Affine3f
Definition: types.hpp:18
kfusion::cuda::TsdfVolume::integrate
virtual void integrate(const Dists &dists, tsdf_buffer &buffer, const Affine3f &camera_pose, const Intr &intr)
Definition: tsdf_volume.cpp:96
kfusion::cuda::TsdfVolume::getPose
Affine3f getPose() const
Definition: tsdf_volume.cpp:64
kfusion::Intr::fy
float fy
Definition: types.hpp:22
kfusion::device::Vec3f
float3 Vec3f
Definition: internal.hpp:26
kfusion::cuda::TsdfVolume::setSize
void setSize(const Vec3f &size)
Definition: tsdf_volume.cpp:45
kfusion::cuda::TsdfVolume::clear
virtual void clear()
Definition: tsdf_volume.cpp:73
kfusion::cuda::TsdfVolume::swap
void swap(CudaData &data)
Definition: tsdf_volume.cpp:70
kfusion::Vec3i
cv::Vec3i Vec3i
Definition: types.hpp:17
kfusion::cuda::TsdfVolume::setGradientDeltaFactor
void setGradientDeltaFactor(float factor)
Definition: tsdf_volume.cpp:69
kfusion::device::Vec3i
int3 Vec3i
Definition: internal.hpp:25
kfusion::cuda::DeviceArray::create
void create(size_t size)
Allocates internal buffer in GPU memory. If internal buffer was created before the function recreates...
Definition: device_array.hpp:241
kfusion::cuda
Definition: device_array.hpp:10
kfusion::cuda::TsdfVolume::setPose
void setPose(const Affine3f &pose)
Definition: tsdf_volume.cpp:65
kfusion
Utility.
Definition: capture.hpp:8
kfusion::cuda::TsdfVolume::getMaxWeight
int getMaxWeight() const
Definition: tsdf_volume.cpp:62
kfusion::device::Mat3f
Definition: internal.hpp:27
kfusion::device::Aff3f
Definition: internal.hpp:28
kfusion::cuda::TsdfVolume::create
void create(const Vec3i &dims)
Definition: tsdf_volume.cpp:24
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::cuda::TsdfVolume::getSize
Vec3f getSize() const
Definition: tsdf_volume.cpp:43
kfusion::cuda::DeviceArray< Point >
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::Intr::cy
float cy
Definition: types.hpp:22
kfusion::cuda::TsdfVolume::setMaxWeight
void setMaxWeight(int weight)
Definition: tsdf_volume.cpp:63
kfusion::cuda::TsdfVolume::Entry::half2float
static float half2float(half value)
TsdfVolume::Entry.
Definition: tsdf_volume.cpp:9
kfusion::cuda::TsdfVolume::raycast
virtual void raycast(const Affine3f &camera_pose, tsdf_buffer &buffer, const Intr &intr, Depth &depth, Normals &normals)
Definition: tsdf_volume.cpp:110
kfusion::device::Projector
Definition: internal.hpp:55
kfusion::cuda::TsdfVolume::Entry::float2half
static half float2half(float value)
Definition: tsdf_volume.cpp:12
kfusion::cuda::TsdfVolume::fetchCloud
DeviceArray< Point > fetchCloud(DeviceArray< Point > &cloud_buffer, const tsdf_buffer &buffer) const
Definition: tsdf_volume.cpp:148
kfusion::cuda::TsdfVolume::Entry::half
unsigned short half
Definition: tsdf_volume.hpp:77
kfusion::tsdf_buffer
Structure to handle buffer addresses.
Definition: tsdf_buffer.h:48
kfusion::device::clearTSDFSlice
void clearTSDFSlice(const TsdfVolume &volume, const kfusion::tsdf_buffer *buffer, const Vec3i offset)
kfusion::cuda::TsdfVolume::getCoord
ushort2 * getCoord(int x, int y, int z, int dim_x, int dim_y)
Definition: tsdf_volume.cpp:57
kfusion::cuda::TsdfVolume::applyAffine
virtual void applyAffine(const Affine3f &affine)
Definition: tsdf_volume.cpp:71
kfusion::cuda::DeviceArray::ptr
T * ptr()
Returns pointer for internal buffer in GPU memory.
Definition: device_array.hpp:259
kfusion::cuda::TsdfVolume::getVoxelSize
Vec3f getVoxelSize() const
Definition: tsdf_volume.cpp:36
kfusion::cuda::TsdfVolume::~TsdfVolume
virtual ~TsdfVolume()
Definition: tsdf_volume.cpp:22
kfusion::Point
Definition: types.hpp:47
kfusion::cuda::TsdfVolume::getRaycastStepFactor
float getRaycastStepFactor() const
Definition: tsdf_volume.cpp:66
kfusion::Intr::cx
float cx
Definition: types.hpp:22
kfusion::cuda::DeviceMemory::empty
bool empty() const
Returns true if unallocated otherwise false.
Definition: device_memory.cpp:138
kfusion::cuda::TsdfVolume::setRaycastStepFactor
void setRaycastStepFactor(float factor)
Definition: tsdf_volume.cpp:67
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::cuda::TsdfVolume::data
const CudaData data() const
Definition: tsdf_volume.cpp:41
kfusion::cuda::DeviceArray2D< unsigned short >
kfusion::Intr::fx
float fx
Definition: types.hpp:22
kfusion::Intr
Definition: types.hpp:20
kfusion::cuda::TsdfVolume::fetchSliceAsCloud
DeviceArray< Point > 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.
Definition: tsdf_volume.cpp:184
kfusion::device::clear_volume
void clear_volume(TsdfVolume volume)
kfusion::cuda::TsdfVolume::fetchNormals
void fetchNormals(const DeviceArray< Point > &cloud, const tsdf_buffer &buffer, DeviceArray< Normal > &normals) const
Definition: tsdf_volume.cpp:167


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