projective_icp.cpp
Go to the documentation of this file.
1 #include <kfusion/precomp.hpp>
2 
3 
4 using namespace kfusion;
5 using namespace std;
6 using namespace kfusion::cuda;
7 
10 
11 kfusion::device::ComputeIcpHelper::ComputeIcpHelper(float dist_thres, float angle_thres)
12 {
13  min_cosine = cos(angle_thres);
14  dist2_thres = dist_thres * dist_thres;
15 }
16 
17 void kfusion::device::ComputeIcpHelper::setLevelIntr(int level_index, float fx, float fy, float cx, float cy)
18 {
19  int div = 1 << level_index;
20  f = make_float2(fx/div, fy/div);
21  c = make_float2(cx/div, cy/div);
22  finv = make_float2(1.f/f.x, 1.f/f.y);
23 }
24 
27 
29 {
31  typedef cv::Matx66f Mat6f;
32  typedef cv::Vec6f Vec6f;
33 
34  cudaStream_t stream;
36 
37  StreamHelper() { cudaSafeCall( cudaStreamCreate(&stream) ); }
38  ~StreamHelper() { cudaSafeCall( cudaStreamDestroy(stream) ); }
39 
40  operator float*() { return locked_buffer.data; }
41  operator cudaStream_t() { return stream; }
42 
44  {
45  cudaSafeCall( cudaStreamSynchronize(stream) );
46 
47  Mat6f A;
48  float *data_A = A.val;
49  float *data_b = b.val;
50 
51  int shift = 0;
52  for (int i = 0; i < 6; ++i) //rows
53  for (int j = i; j < 7; ++j) // cols + b
54  {
55  float value = locked_buffer.data[shift++];
56  if (j == 6) // vector b
57  data_b[i] = value;
58  else
59  data_A[j * 6 + i] = data_A[i * 6 + j] = value;
60  }
61  return A;
62  }
63 };
64 
67 
68 kfusion::cuda::ProjectiveICP::ProjectiveICP() : angle_thres_(deg2rad(20.f)), dist_thres_(0.1f)
69 {
70  const int iters[] = {10, 5, 4, 0};
71  std::vector<int> vector_iters(iters, iters + 4);
72  setIterationsNum(vector_iters);
74 
75  shelp_ = cv::Ptr<StreamHelper>(new StreamHelper());
76 }
77 
79 
81 { return dist_thres_; }
82 
84 { dist_thres_ = distance; }
85 
87 { return angle_thres_; }
88 
90 { angle_thres_ = angle; }
91 
92 void kfusion::cuda::ProjectiveICP::setIterationsNum(const std::vector<int>& iters)
93 {
94  if (iters.size() >= MAX_PYRAMID_LEVELS)
95  iters_.assign(iters.begin(), iters.begin() + MAX_PYRAMID_LEVELS);
96  else
97  {
98  iters_ = vector<int>(MAX_PYRAMID_LEVELS, 0);
99  copy(iters.begin(), iters.end(),iters_.begin());
100  }
101 }
102 
104 {
105  int i = MAX_PYRAMID_LEVELS - 1;
106  for(; i >= 0 && !iters_[i]; --i);
107  return i + 1;
108 }
109 
110 bool kfusion::cuda::ProjectiveICP::estimateTransform(Affine3f& /*affine*/, const Intr& /*intr*/, const Frame& /*curr*/, const Frame& /*prev*/)
111 {
112 // bool has_depth = !curr.depth_pyr.empty() && !prev.depth_pyr.empty();
113 // bool has_points = !curr.points_pyr.empty() && !prev.points_pyr.empty();
114 
115 // if (has_depth)
116 // return estimateTransform(affine, intr, curr.depth_pyr, curr.normals_pyr, prev.depth_pyr, prev.normals_pyr);
117 // else if(has_points)
118 // return estimateTransform(affine, intr, curr.points_pyr, curr.normals_pyr, prev.points_pyr, prev.normals_pyr);
119 // else
120 // CV_Assert(!"Wrong parameters passed to estimateTransform");
121  CV_Assert(!"Not implemented");
122  return false;
123 }
124 
125 bool kfusion::cuda::ProjectiveICP::estimateTransform(Affine3f& affine, const Intr& intr, const DepthPyr& dcurr, const NormalsPyr ncurr, const DepthPyr dprev, const NormalsPyr nprev)
126 {
127  const int LEVELS = getUsedLevelsNum();
128  StreamHelper& sh = *shelp_;
129 
130  device::ComputeIcpHelper helper(dist_thres_, angle_thres_);
131  affine = Affine3f::Identity();
132 
133  for(int level_index = LEVELS - 1; level_index >= 0; --level_index)
134  {
135  const device::Normals& n = (const device::Normals& )nprev[level_index];
136 
137  helper.rows = (float)n.rows();
138  helper.cols = (float)n.cols();
139  helper.setLevelIntr(level_index, intr.fx, intr.fy, intr.cx, intr.cy);
140  helper.dcurr = dcurr[level_index];
141  helper.ncurr = ncurr[level_index];
142 
143  for(int iter = 0; iter < iters_[level_index]; ++iter)
144  {
145  helper.aff = device_cast<device::Aff3f>(affine);
146  helper(dprev[level_index], n, buffer_, sh, sh);
147 
149  StreamHelper::Mat6f A = sh.get(b);
150 
151  //checking nullspace
152  double det = cv::determinant(A);
153 
154  if (fabs (det) < 1e-15 || cv::viz::isNan(det))
155  {
156  if (cv::viz::isNan(det)) cout << "qnan" << endl;
157  return false;
158  }
159 
161  cv::solve(A, b, r, cv::DECOMP_SVD);
162  Affine3f Tinc(Vec3f(r.val), Vec3f(r.val+3));
163  affine = Tinc * affine;
164  }
165  }
166  return true;
167 }
168 
169 bool kfusion::cuda::ProjectiveICP::estimateTransform(Affine3f& affine, const Intr& intr, const PointsPyr& vcurr, const NormalsPyr ncurr, const PointsPyr vprev, const NormalsPyr nprev)
170 {
171  const int LEVELS = getUsedLevelsNum();
172  StreamHelper& sh = *shelp_;
173 
174  device::ComputeIcpHelper helper(dist_thres_, angle_thres_);
175  affine = Affine3f::Identity();
176 
177  for(int level_index = LEVELS - 1; level_index >= 0; --level_index)
178  {
179  const device::Normals& n = (const device::Normals& )nprev[level_index];
180  const device::Points& v = (const device::Points& )vprev[level_index];
181 
182  helper.rows = (float)n.rows();
183  helper.cols = (float)n.cols();
184  helper.setLevelIntr(level_index, intr.fx, intr.fy, intr.cx, intr.cy);
185  helper.vcurr = vcurr[level_index];
186  helper.ncurr = ncurr[level_index];
187 
188  for(int iter = 0; iter < iters_[level_index]; ++iter)
189  {
190  helper.aff = device_cast<device::Aff3f>(affine);
191  helper(v, n, buffer_, sh, sh);
192 
194  StreamHelper::Mat6f A = sh.get(b);
195 
196  //checking nullspace
197  double det = cv::determinant(A);
198 
199  if (fabs (det) < 1e-15 || cv::viz::isNan (det))
200  {
201  if (cv::viz::isNan (det)) cout << "qnan" << endl;
202  return false;
203  }
204 
206  cv::solve(A, b, r, cv::DECOMP_SVD);
207 
208  Affine3f Tinc(Vec3f(r.val), Vec3f(r.val+3));
209  affine = Tinc * affine;
210  }
211  }
212  return true;
213 }
214 
kfusion::cuda::ProjectiveICP::setDistThreshold
void setDistThreshold(float distance)
Definition: projective_icp.cpp:83
kfusion::cuda::ProjectiveICP::setIterationsNum
void setIterationsNum(const std::vector< int > &iters)
Definition: projective_icp.cpp:92
kfusion::Vec3f
cv::Vec3f Vec3f
Definition: types.hpp:16
kfusion::cuda::ProjectiveICP::getDistThreshold
float getDistThreshold() const
Definition: projective_icp.cpp:80
kfusion::device::ComputeIcpHelper::allocate_buffer
static void allocate_buffer(DeviceArray2D< float > &buffer, int partials_count=-1)
kfusion::cuda::DeviceArray2D::cols
int cols() const
Returns number of elements in each row.
Definition: device_array.hpp:300
kfusion::cuda::ProjectiveICP::StreamHelper::get
Mat6f get(Vec6f &b)
Definition: projective_icp.cpp:43
precomp.hpp
kfusion::Affine3f
cv::Affine3f Affine3f
Definition: types.hpp:18
kfusion::cuda::ProjectiveICP::NormalsPyr
std::vector< Normals > NormalsPyr
Definition: projective_icp.hpp:16
kfusion::Intr::fy
float fy
Definition: types.hpp:22
kfusion::cuda::ProjectiveICP::getAngleThreshold
float getAngleThreshold() const
Definition: projective_icp.cpp:86
kfusion::device::ComputeIcpHelper::rows
float rows
Definition: internal.hpp:86
kfusion::cuda::ProjectiveICP::StreamHelper::~StreamHelper
~StreamHelper()
Definition: projective_icp.cpp:38
kfusion::cuda::ProjectiveICP::DepthPyr
std::vector< Depth > DepthPyr
Definition: projective_icp.hpp:14
kfusion::cuda
Definition: device_array.hpp:10
kfusion
Utility.
Definition: capture.hpp:8
kfusion::device::ComputeIcpHelper::vcurr
PtrStep< Point > vcurr
Definition: internal.hpp:91
kfusion::cuda::ProjectiveICP::PointsPyr
std::vector< Cloud > PointsPyr
Definition: projective_icp.hpp:15
kfusion::cuda::Frame
Definition: types.hpp:91
kfusion::Intr::cy
float cy
Definition: types.hpp:22
kfusion::device::ComputeIcpHelper::ComputeIcpHelper
ComputeIcpHelper(float dist_thres, float angle_thres)
ComputeIcpHelper.
Definition: projective_icp.cpp:11
kfusion::cuda::ProjectiveICP::StreamHelper::locked_buffer
PageLockHelper locked_buffer
Definition: projective_icp.cpp:35
kfusion::cuda::ProjectiveICP::estimateTransform
virtual bool estimateTransform(Affine3f &affine, const Intr &intr, const Frame &curr, const Frame &prev)
Definition: projective_icp.cpp:110
kfusion::cuda::ProjectiveICP::buffer_
DeviceArray2D< float > buffer_
Definition: projective_icp.hpp:42
kfusion::device::ComputeIcpHelper::cols
float cols
Definition: internal.hpp:86
kfusion::cuda::DeviceArray2D::rows
int rows() const
Returns number of rows.
Definition: device_array.hpp:301
kfusion::cuda::ProjectiveICP::StreamHelper::Mat6f
cv::Matx66f Mat6f
Definition: projective_icp.cpp:31
kfusion::device::ComputeIcpHelper::PageLockHelper
Definition: internal.hpp:74
kfusion::device::ComputeIcpHelper
Definition: internal.hpp:71
kfusion::device::ComputeIcpHelper::ncurr
PtrStep< Normal > ncurr
Definition: internal.hpp:90
kfusion::cuda::ProjectiveICP::getUsedLevelsNum
int getUsedLevelsNum() const
Definition: projective_icp.cpp:103
std
Definition: HalfEdge.hpp:124
kfusion::cuda::ProjectiveICP::StreamHelper::stream
cudaStream_t stream
Definition: projective_icp.cpp:34
kfusion::cuda::ProjectiveICP::ProjectiveICP
ProjectiveICP()
ProjectiveICP.
Definition: projective_icp.cpp:68
kfusion::device::ComputeIcpHelper::PageLockHelper::data
float * data
Definition: internal.hpp:76
kfusion::Intr::cx
float cx
Definition: types.hpp:22
kfusion::cuda::ProjectiveICP::shelp_
cv::Ptr< StreamHelper > shelp_
Definition: projective_icp.hpp:44
cudaSafeCall
#define cudaSafeCall(expr)
Definition: safe_call.hpp:16
kfusion::deg2rad
float deg2rad(float alpha)
Definition: types.hpp:101
kfusion::cuda::ProjectiveICP::StreamHelper::PageLockHelper
device::ComputeIcpHelper::PageLockHelper PageLockHelper
Definition: projective_icp.cpp:30
kfusion::cuda::ProjectiveICP::StreamHelper
ProjectiveICP::StreamHelper.
Definition: projective_icp.cpp:28
kfusion::cuda::ProjectiveICP::StreamHelper::Vec6f
cv::Vec6f Vec6f
Definition: projective_icp.cpp:32
kfusion::cuda::ProjectiveICP::~ProjectiveICP
virtual ~ProjectiveICP()
Definition: projective_icp.cpp:78
kfusion::cuda::ProjectiveICP::StreamHelper::StreamHelper
StreamHelper()
Definition: projective_icp.cpp:37
kfusion::cuda::DeviceArray2D
DeviceArray2D class
Definition: device_array.hpp:117
kfusion::Intr::fx
float fx
Definition: types.hpp:22
kfusion::Intr
Definition: types.hpp:20
kfusion::cuda::ProjectiveICP::setAngleThreshold
void setAngleThreshold(float angle)
Definition: projective_icp.cpp:89
kfusion::device::ComputeIcpHelper::setLevelIntr
void setLevelIntr(int level_index, float fx, float fy, float cx, float cy)
Definition: projective_icp.cpp:17
kfusion::device::ComputeIcpHelper::aff
Aff3f aff
Definition: internal.hpp:84
kfusion::device::ComputeIcpHelper::dcurr
PtrStep< ushort > dcurr
Definition: internal.hpp:89


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