types.hpp
Go to the documentation of this file.
1 #pragma once
2 
4 #include <kfusion/Options.hpp>
5 #include <opencv2/core/core.hpp>
6 #include <opencv2/contrib/contrib.hpp>
7 #include <opencv2/core/affine.hpp>
8 #include <opencv2/viz/vizcore.hpp>
9 #include <iosfwd>
10 
11 struct CUevent_st;
12 
13 namespace kfusion
14 {
15  typedef cv::Matx33f Mat3f;
16  typedef cv::Vec3f Vec3f;
17  typedef cv::Vec3i Vec3i;
19 
21  {
22  float fx, fy, cx, cy;
23 
24  Intr ();
25  Intr (float fx, float fy, float cx, float cy);
26  Intr operator()(int level_index) const;
27  };
28 
30  {
31  cv::Mat image;
32  Affine3f pose;
33  cv::Mat intrinsics;
34  cv::Mat distortion;
35  };
36 
38  {
39  cv::Mat tsdf_values_;
40  Vec3i offset_;
41  Vec3i back_offset_;
42  std::vector<ImgPose*> imgposes_;
43  };
44 
45  KF_EXPORTS std::ostream& operator << (std::ostream& os, const Intr& intr);
46 
47  struct Point
48  {
49  union
50  {
51  float data[4];
52  struct { float x, y, z, w; };
53  };
54 
55  Point& operator+(cv::Vec<float, 3> vec)
56  {
57  this->x += vec[0];
58  this->y += vec[1];
59  this->z += vec[2];
60  return *this;
61  }
62  };
63 
64  typedef Point Normal;
65 
66  KF_EXPORTS std::ostream& operator << (std::ostream& os, const kfusion::Point& p);
67 
68  struct RGB
69  {
70  union
71  {
72  struct { unsigned char b, g, r; };
73  int bgra;
74  };
75  };
76 
77  struct PixelRGB
78  {
79  unsigned char r, g, b;
80  };
81 
82  namespace cuda
83  {
90 
91  struct Frame
92  {
93  bool use_points;
94 
95  std::vector<Depth> depth_pyr;
96  std::vector<Cloud> points_pyr;
97  std::vector<Normals> normals_pyr;
98  };
99  }
100 
101  inline float deg2rad (float alpha) { return alpha * 0.017453293f; }
102 
104  {
105  const char* name;
106  double start;
107  ScopeTime(const char *name);
108  ~ScopeTime();
109  double getTime();
110  };
111 
113  {
114  public:
115  enum { EACH = 33 };
116  SampledScopeTime(double& time_ms);
117  ~SampledScopeTime();
118  private:
119  double getTime();
121  SampledScopeTime& operator=(const SampledScopeTime&);
122 
123  double& time_ms_;
124  double start;
125  };
126 
128  {
129  static KinFuParams default_params();
130 
131  int cols; //pixels
132  int rows; //pixels
133 
134  Intr intr; //Camera parameters
135  //Intr intr_rgb; //Camera parameters
136 
137  Vec3i volume_dims; //number of voxels
138  Vec3f volume_size; //meters
139  Affine3f volume_pose; //meters, inital pose
140 
143 
144  float bilateral_sigma_depth; //meters
145  float bilateral_sigma_spatial; //pixels
146  int bilateral_kernel_size; //pixels
147 
148  float icp_truncate_depth_dist; //meters
149  float icp_dist_thres; //meters
150  float icp_angle_thres; //radians
151  std::vector<int> icp_iter_num; //iterations for level index 0,1,..,3
152 
153  float tsdf_min_camera_movement; //meters, integrate only if exceedes
154  float tsdf_trunc_dist; //meters;
155  int tsdf_max_weight; //frames
156 
157  float raycast_step_factor; // in voxel sizes
158  float gradient_delta_factor; // in voxel sizes
159 
160  Vec3f light_pose; //meters
161 
162  Options* cmd_options; // cmd_options
163 
164  };
165 
166 }
cuda::DeviceArray2D< Normal > Normals
Definition: types.hpp:88
cv::Mat image
Definition: types.hpp:31
cv::Vec3f Vec3f
Definition: types.hpp:16
cv::Mat intrinsics
Definition: types.hpp:33
cv::Affine3f Affine3f
Definition: types.hpp:18
float icp_truncate_depth_dist
Definition: types.hpp:148
unsigned char r
Definition: types.hpp:79
Point & operator+(cv::Vec< float, 3 > vec)
Definition: types.hpp:55
std::vector< Depth > depth_pyr
Definition: types.hpp:95
unsigned char r
Definition: types.hpp:72
A class to parse the program options for the reconstruction executable.
int bgra
Definition: types.hpp:73
cv::Matx33f Mat3f
Definition: types.hpp:15
cuda::DeviceArray2D< unsigned short > Depth
Definition: types.hpp:85
float bilateral_sigma_depth
Definition: types.hpp:144
std::vector< ImgPose * > imgposes_
Definition: types.hpp:42
cv::Vec3i Vec3i
Definition: types.hpp:17
double distance_camera_target
Definition: types.hpp:142
cuda::DeviceArray2D< RGB > Image
Definition: types.hpp:87
cv::Mat tsdf_values_
Definition: types.hpp:39
Options * cmd_options
Definition: types.hpp:162
std::vector< Cloud > points_pyr
Definition: types.hpp:96
float tsdf_min_camera_movement
Definition: types.hpp:153
cuda::DeviceMemory CudaData
Definition: types.hpp:84
SharedPointer p
#define KF_EXPORTS
Definition: exports.hpp:6
float raycast_step_factor
Definition: types.hpp:157
ostream & operator<<(ostream &os, const Options &o)
Overlaoeded outpur operator.
float shifting_distance
Definition: types.hpp:141
Vec3i back_offset_
Definition: types.hpp:41
cuda::DeviceArray2D< unsigned short > Dists
Definition: types.hpp:86
Affine3f volume_pose
Definition: types.hpp:139
float fy
Definition: types.hpp:22
std::vector< Normals > normals_pyr
Definition: types.hpp:97
float gradient_delta_factor
Definition: types.hpp:158
float deg2rad(float alpha)
Definition: types.hpp:101
float bilateral_sigma_spatial
Definition: types.hpp:145
Point Normal
Definition: types.hpp:64
Affine3f pose
Definition: types.hpp:32
cv::Mat distortion
Definition: types.hpp:34
Utility.
Definition: capture.hpp:8
cuda::DeviceArray2D< Point > Cloud
Definition: types.hpp:89
std::vector< int > icp_iter_num
Definition: types.hpp:151
const char * name
Definition: types.hpp:105


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