tsdf_volume.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 #include <kfusion/types.hpp>
4 #include <kfusion/tsdf_buffer.h>
5 #include <cuda_runtime.h>
6 
7 namespace kfusion
8 {
9  namespace cuda
10  {
12  {
13  public:
14  TsdfVolume(const cv::Vec3i& dims);
15  virtual ~TsdfVolume();
16 
17  void create(const Vec3i& dims);
18 
19  Vec3i getDims() const;
20  Vec3f getVoxelSize() const;
21 
22  const CudaData data() const;
23  CudaData data();
24 
25  Vec3f getSize() const;
26  void setSize(const Vec3f& size);
27 
28  float getTruncDist() const;
29  void setTruncDist(float distance);
30 
31  int getMaxWeight() const;
32  void setMaxWeight(int weight);
33 
34  Affine3f getPose() const;
35  void setPose(const Affine3f& pose);
36 
37  float getRaycastStepFactor() const;
38  void setRaycastStepFactor(float factor);
39 
40  ushort2* getCoord(int x, int y, int z, int dim_x, int dim_y);
41 
42 
43  float getGradientDeltaFactor() const;
44  void setGradientDeltaFactor(float factor);
45 
46  Vec3i getGridOrigin() const;
47  void setGridOrigin(const Vec3i& origin);
48 
49  void clearSlice(const kfusion::tsdf_buffer* buffer, const Vec3i offset) const;
50 
51 
52  virtual void clear();
53  virtual void applyAffine(const Affine3f& affine);
54  virtual void integrate(const Dists& dists, tsdf_buffer& buffer, const Affine3f& camera_pose, const Intr& intr);
55  virtual void raycast(const Affine3f& camera_pose, tsdf_buffer& buffer, const Intr& intr, Depth& depth, Normals& normals);
56  virtual void raycast(const Affine3f& camera_pose, tsdf_buffer& buffer, const Intr& intr, Cloud& points, Normals& normals);
57 
68  fetchSliceAsCloud (DeviceArray<Point>& cloud_buffer, const kfusion::tsdf_buffer* buffer, const Vec3i minBounds, const Vec3i maxBounds, const Vec3i globalShift ) const;
69 
70  void swap(CudaData& data);
71 
72  DeviceArray<Point> fetchCloud(DeviceArray<Point>& cloud_buffer, const tsdf_buffer& buffer) const;
73  void fetchNormals(const DeviceArray<Point>& cloud, const tsdf_buffer& buffer, DeviceArray<Normal>& normals) const;
74 
75  struct Entry
76  {
77  typedef unsigned short half;
78 
79  half tsdf;
80  unsigned short weight;
81 
82  static float half2float(half value);
83  static half float2half(float value);
84  };
85  private:
87 
88  float trunc_dist_;
93 
96  };
97  }
98 }
cv::Vec3f Vec3f
Definition: types.hpp:16
Structure to handle buffer addresses.
Definition: tsdf_buffer.h:48
cv::Affine3f Affine3f
Definition: types.hpp:18
__kf_hdevice__ void swap(T &a, T &b)
Definition: temp_utils.hpp:10
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 integrate(const Dists &depth, TsdfVolume &volume, tsdf_buffer &buffer, const Aff3f &aff, const Projector &proj)
cv::Vec3i Vec3i
Definition: types.hpp:17
#define KF_EXPORTS
Definition: exports.hpp:6
Utility.
Definition: capture.hpp:8


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 Mon Feb 28 2022 22:46:09