cyclical_buffer.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2010-2011, Willow Garage, Inc.
6  *
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of Willow Garage, Inc. nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  */
37  /*
38  * cyclical_buffer.h
39  *
40  * @date 13.11.2015
41  * @author Tristan Igelbrink (Tristan@Igelbrink.com)
42  */
43 
44 
45 #ifndef CYCLICAL_BUFFER_IMPL_H_
46 #define CYCLICAL_BUFFER_IMPL_H_
47 
49 #include <kfusion/tsdf_buffer.h>
50 #include <kfusion/LVRPipeline.hpp>
51 #include <Eigen/Core>
52 #include "types.hpp"
53 #include <cuda_runtime.h>
54 #include <thread>
55 
56 namespace kfusion
57 {
58  namespace cuda
59  {
65  {
66 
67  public:
73  CyclicalBuffer (KinFuParams params): pl_(params),
74  optimize_(params.cmd_options->optimizePlanes()), no_reconstruct_(params.cmd_options->noReconstruction())
75  {
76  distance_threshold_ = params.shifting_distance;
77  buffer_.volume_size.x = params.volume_size[0];
78  buffer_.volume_size.y = params.volume_size[1];
79  buffer_.volume_size.z = params.volume_size[2];
80  buffer_.voxels_size.x = params.volume_dims[0];
81  buffer_.voxels_size.y = params.volume_dims[1];
82  buffer_.voxels_size.z = params.volume_dims[2];
83  global_shift_[0] = 0;
84  global_shift_[1] = 0;
85  global_shift_[2] = 0;
86  }
87 
88 
98  /*CyclicalBuffer (const double distance_threshold,
99  const double volume_size_x, const double volume_size_y,
100  const double volume_size_z, const int nb_voxels_x, const int nb_voxels_y,
101  const int nb_voxels_z)
102  {
103  distance_threshold_ = distance_threshold;
104  buffer_.volume_size.x = volume_size_x;
105  buffer_.volume_size.y = volume_size_y;
106  buffer_.volume_size.z = volume_size_z;
107  buffer_.voxels_size.x = nb_voxels_x;
108  buffer_.voxels_size.y = nb_voxels_y;
109  buffer_.voxels_size.z = nb_voxels_z;
110  }*/
111 
113  {
114  //double averageMCTime = mcwrap_.calcTimeStats();
115  //cout << "----- Average time for processing one tsdf value " << averageMCTime << "ns -----" << endl;
116  }
117 
129  bool checkForShift (cv::Ptr<cuda::TsdfVolume> volume,
130  const Affine3f &cam_pose, const double distance_camera_target,
131  const bool perform_shift = true, const bool last_shift = false,
132  const bool record_mode = false);
133 
146  void performShift (cv::Ptr<cuda::TsdfVolume> volume, const cv::Vec3f& target_point, const Affine3f &cam_pose, const bool last_shift = false, const bool record_mode = false);
147 
151  void setDistanceThreshold (const double threshold)
152  {
153  distance_threshold_ = threshold;
154  }
155 
157  float getDistanceThreshold () { return (distance_threshold_); }
158 
162  tsdf_buffer& getBuffer () { return (buffer_); }
163 
169  void setVolumeSize (const Vec3f size)
170  {
171  buffer_.volume_size.x = size[0];
172  buffer_.volume_size.y = size[1];
173  buffer_.volume_size.z = size[2];
174  }
175 
176  void setVoxelSize (const Vec3f vsize)
177  {
178  buffer_.voxels_size.x = vsize[0];
179  buffer_.voxels_size.y = vsize[1];
180  buffer_.voxels_size.z = vsize[2];
181  }
182 
184  {
185  return Vec3f(buffer_.origin_metric.x, buffer_.origin_metric.y, buffer_.origin_metric.z);
186  }
187 
191  void setVolumeSize (const double size)
192  {
193  buffer_.volume_size.x = size;
194  buffer_.volume_size.y = size;
195  buffer_.volume_size.z = size;
196  }
197 
204  void computeAndSetNewCubeMetricOrigin (cv::Ptr<cuda::TsdfVolume> volume, const cv::Vec3f& target_point, Vec3i& offset);
205 
209  void initBuffer (cv::Ptr<cuda::TsdfVolume> tsdf_volume)
210  {
211  buffer_.tsdf_memory_start = tsdf_volume->getCoord(0, 0, 0, 0, 0);
212  buffer_.tsdf_memory_end = tsdf_volume->getCoord(buffer_.voxels_size.x - 1, buffer_.voxels_size.y - 1, buffer_.voxels_size.z - 1, buffer_.voxels_size.x, buffer_.voxels_size.y);
213 
214  buffer_.tsdf_rolling_buff_origin = buffer_.tsdf_memory_start;
215  }
216 
220  void resetBuffer (cv::Ptr<cuda::TsdfVolume> tsdf_volume)
221  {
222  buffer_.origin_GRID.x = 0; buffer_.origin_GRID.y = 0; buffer_.origin_GRID.z = 0;
223  buffer_.origin_GRID_global.x = 0.f; buffer_.origin_GRID_global.y = 0.f; buffer_.origin_GRID_global.z = 0.f;
224  Vec3f position = tsdf_volume->getPose().translation();
225  buffer_.origin_metric.x = position[0];
226  buffer_.origin_metric.y = position[1];
227  buffer_.origin_metric.z = position[2];
228  initBuffer (tsdf_volume);
229  }
230 
231  void resetMesh(){/*mcwrap_.resetMesh();*/}
232  void addImgPose(ImgPose* imgPose){ imgPoses_.push_back(imgPose);}
233 
234  MeshPtr getMesh() {return pl_.getMesh();}
235 
236  int getSliceCount(){return slice_count_;}
237 
238 
239  private:
240 
243 
247  cv::Mat cloud_slice_;
248  std::vector<ImgPose*> imgPoses_;
249  int slice_count_ = 0;
251  bool optimize_, no_reconstruct_;
252 
255 
256  //MaCuWrapper mcwrap_;
258  inline int calcIndex(float f) const
259  {
260  return f < 0 ? f-.5:f+.5;
261  }
262 
263  float euclideanDistance(const Point& p1, const Point& p2);
264 
265  void getEulerYPR(float& yaw, float& pitch, float& roll, cv::Affine3<float>::Mat3& mat, unsigned int solution_number = 1);
266 
267  void calcBounds(Vec3i& offset, Vec3i& minBounds, Vec3i& maxBounds);
268 
275  void shiftOrigin (cv::Ptr<cuda::TsdfVolume> tsdf_volume, Vec3i offset)
276  {
277  // shift rolling origin (making sure they keep in [0 - NbVoxels[ )
278  buffer_.origin_GRID.x += offset[0];
279  if(buffer_.origin_GRID.x >= buffer_.voxels_size.x)
280  buffer_.origin_GRID.x -= buffer_.voxels_size.x;
281  else if(buffer_.origin_GRID.x < 0)
282  {
283  buffer_.origin_GRID.x += buffer_.voxels_size.x ;
284  }
285 
286  buffer_.origin_GRID.y += offset[1];
287  if(buffer_.origin_GRID.y >= buffer_.voxels_size.y)
288  buffer_.origin_GRID.y -= buffer_.voxels_size.y;
289  else if(buffer_.origin_GRID.y < 0)
290  {
291  buffer_.origin_GRID.y += buffer_.voxels_size.y;
292  }
293 
294  buffer_.origin_GRID.z += offset[2];
295  if(buffer_.origin_GRID.z >= buffer_.voxels_size.z)
296  buffer_.origin_GRID.z -= buffer_.voxels_size.z;
297  else if(buffer_.origin_GRID.z < 0)
298  {
299  buffer_.origin_GRID.z += buffer_.voxels_size.z;
300  }
301  // update memory pointers
302  CudaData localVolume = tsdf_volume->data();
303  buffer_.tsdf_memory_start = tsdf_volume->getCoord(0, 0, 0, 0, 0);
304  buffer_.tsdf_memory_end = tsdf_volume->getCoord(buffer_.voxels_size.x - 1, buffer_.voxels_size.y - 1, buffer_.voxels_size.z - 1, buffer_.voxels_size.x, buffer_.voxels_size.y);
305  buffer_.tsdf_rolling_buff_origin = tsdf_volume->getCoord(buffer_.origin_GRID.x, buffer_.origin_GRID.y, buffer_.origin_GRID.z, buffer_.voxels_size.x, buffer_.voxels_size.y);
306 
307  // update global origin
308  global_shift_[0] = buffer_.origin_GRID_global.x += offset[0];
309  global_shift_[1] = buffer_.origin_GRID_global.y += offset[1];
310  global_shift_[2] = buffer_.origin_GRID_global.z += offset[2];
311  }
312 
313  };
314  }
315 }
316 
317 #endif // CYCLICAL_BUFFER_IMPL_H_
kfusion::tsdf_buffer::tsdf_memory_start
ushort2 * tsdf_memory_start
Address of the first element of the TSDF volume in memory.
Definition: tsdf_buffer.h:52
kfusion::tsdf_buffer::tsdf_rolling_buff_origin
ushort2 * tsdf_rolling_buff_origin
Memory address of the origin of the rolling buffer. MUST BE UPDATED AFTER EACH SHIFT.
Definition: tsdf_buffer.h:56
kfusion::cuda::CyclicalBuffer::pl_
LVRPipeline pl_
Definition: cyclical_buffer.h:257
kfusion::cuda::CyclicalBuffer::CyclicalBuffer
CyclicalBuffer(KinFuParams params)
Constructor for a cubic CyclicalBuffer.
Definition: cyclical_buffer.h:73
kfusion::Vec3f
cv::Vec3f Vec3f
Definition: types.hpp:16
kfusion::LVRPipeline
Definition: LVRPipeline.hpp:32
kfusion::cuda::CyclicalBuffer::getSliceCount
int getSliceCount()
Definition: cyclical_buffer.h:236
types.hpp
kfusion::cuda::CyclicalBuffer::initBuffer
void initBuffer(cv::Ptr< cuda::TsdfVolume > tsdf_volume)
Initializes memory pointers of the cyclical buffer (start, end, current origin)
Definition: cyclical_buffer.h:209
tsdf_volume.hpp
kfusion::cuda::CyclicalBuffer::buffer_
tsdf_buffer buffer_
structure that contains all TSDF buffer's addresses
Definition: cyclical_buffer.h:254
kfusion::cuda::DeviceMemory
DeviceMemory class
Definition: device_memory.hpp:21
LVRPipeline.hpp
kfusion::Affine3f
cv::Affine3f Affine3f
Definition: types.hpp:18
kfusion::cuda::CyclicalBuffer::getMesh
MeshPtr getMesh()
Definition: cyclical_buffer.h:234
kfusion::cuda::CyclicalBuffer::setVolumeSize
void setVolumeSize(const double size)
Set the physical size represented by the default TSDF volume.
Definition: cyclical_buffer.h:191
kfusion::device::Vec3f
float3 Vec3f
Definition: internal.hpp:26
kfusion::cuda::CyclicalBuffer::getBuffer
tsdf_buffer & getBuffer()
get a pointer to the tsdf_buffer structure.
Definition: cyclical_buffer.h:162
kfusion::cuda::CyclicalBuffer
CyclicalBuffer implements a cyclical TSDF buffer. The class offers a simple interface,...
Definition: cyclical_buffer.h:64
kfusion::cuda::CyclicalBuffer::cloud_buffer_device_
DeviceArray< Point > cloud_buffer_device_
buffer used to extract XYZ values from GPU
Definition: cyclical_buffer.h:242
kfusion::Vec3i
cv::Vec3i Vec3i
Definition: types.hpp:17
kfusion::cuda::CyclicalBuffer::distance_threshold_
double distance_threshold_
distance threshold (cube's center to target point) to trigger shift
Definition: cyclical_buffer.h:245
kfusion::cuda::CyclicalBuffer::shiftOrigin
void shiftOrigin(cv::Ptr< cuda::TsdfVolume > tsdf_volume, Vec3i offset)
updates cyclical buffer origins given offsets on X, Y and Z
Definition: cyclical_buffer.h:275
kfusion::tsdf_buffer::voxels_size
int3 voxels_size
Number of voxels in the volume, per axis.
Definition: tsdf_buffer.h:66
kfusion::tsdf_buffer::tsdf_memory_end
ushort2 * tsdf_memory_end
Address of the last element of the TSDF volume in memory.
Definition: tsdf_buffer.h:54
kfusion::tsdf_buffer::origin_GRID_global
float3 origin_GRID_global
Cube origin in world coordinates.
Definition: tsdf_buffer.h:60
kfusion
Utility.
Definition: capture.hpp:8
kfusion::cuda::CyclicalBuffer::addImgPose
void addImgPose(ImgPose *imgPose)
Definition: cyclical_buffer.h:232
kfusion::cuda::CyclicalBuffer::~CyclicalBuffer
~CyclicalBuffer()
Constructor for a non-cubic CyclicalBuffer.
Definition: cyclical_buffer.h:112
kfusion::cuda::DeviceArray< Point >
kfusion::cuda::CyclicalBuffer::setDistanceThreshold
void setDistanceThreshold(const double threshold)
Sets the distance threshold between cube's center and target point that triggers a shift.
Definition: cyclical_buffer.h:151
kfusion::cuda::CyclicalBuffer::optimize_
bool optimize_
Definition: cyclical_buffer.h:251
kfusion::cuda::CyclicalBuffer::resetBuffer
void resetBuffer(cv::Ptr< cuda::TsdfVolume > tsdf_volume)
Reset buffer structure.
Definition: cyclical_buffer.h:220
kfusion::KinFuParams
Definition: types.hpp:127
kfusion::cuda::CyclicalBuffer::global_shift_
Vec3i global_shift_
Definition: cyclical_buffer.h:246
kfusion::tsdf_buffer
Structure to handle buffer addresses.
Definition: tsdf_buffer.h:48
kfusion::KinFuParams::volume_size
Vec3f volume_size
Definition: types.hpp:138
kfusion::KinFuParams::volume_dims
Vec3i volume_dims
Definition: types.hpp:137
kfusion::tsdf_buffer::origin_GRID
int3 origin_GRID
Internal cube origin for rollign buffer.
Definition: tsdf_buffer.h:58
MeshPtr
HMesh * MeshPtr
Definition: FusionStage.hpp:63
kfusion::KinFuParams::shifting_distance
float shifting_distance
Definition: types.hpp:141
kfusion::Point
Definition: types.hpp:47
kfusion::cuda::CyclicalBuffer::calcIndex
int calcIndex(float f) const
Definition: cyclical_buffer.h:258
tsdf_buffer.h
kfusion::cuda::CyclicalBuffer::getOrigin
Vec3f getOrigin()
Definition: cyclical_buffer.h:183
kfusion::cuda::CyclicalBuffer::setVolumeSize
void setVolumeSize(const Vec3f size)
Set the physical size represented by the default TSDF volume.
Definition: cyclical_buffer.h:169
kfusion::cuda::CyclicalBuffer::setVoxelSize
void setVoxelSize(const Vec3f vsize)
Definition: cyclical_buffer.h:176
kfusion::cuda::CyclicalBuffer::imgPoses_
std::vector< ImgPose * > imgPoses_
Definition: cyclical_buffer.h:248
kfusion::ImgPose
Definition: types.hpp:29
kfusion::cuda::CyclicalBuffer::getDistanceThreshold
float getDistanceThreshold()
Returns the distance threshold between cube's center and target point that triggers a shift.
Definition: cyclical_buffer.h:157
kfusion::cuda::CyclicalBuffer::cloud_slice_
cv::Mat cloud_slice_
Definition: cyclical_buffer.h:247
kfusion::cuda::CyclicalBuffer::resetMesh
void resetMesh()
Definition: cyclical_buffer.h:231
kfusion::cuda::CyclicalBuffer::last_camPose_
Affine3f last_camPose_
Definition: cyclical_buffer.h:250
KF_EXPORTS
#define KF_EXPORTS
Definition: exports.hpp:6


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