45 #ifndef CYCLICAL_BUFFER_IMPL_H_ 
   46 #define CYCLICAL_BUFFER_IMPL_H_ 
   53 #include <cuda_runtime.h> 
   74                                         optimize_(params.cmd_options->optimizePlanes()), no_reconstruct_(params.cmd_options->noReconstruction())
 
  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);
 
  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);
 
  153                           distance_threshold_ = threshold;
 
  171                                 buffer_.volume_size.x = size[0];
 
  172                                 buffer_.volume_size.y = size[1];
 
  173                                 buffer_.volume_size.z = size[2];
 
  178                                 buffer_.voxels_size.x = vsize[0];
 
  179                                 buffer_.voxels_size.y = vsize[1];
 
  180                                 buffer_.voxels_size.z = vsize[2];
 
  185                                 return Vec3f(buffer_.origin_metric.x, buffer_.origin_metric.y, buffer_.origin_metric.z);
 
  193                         buffer_.volume_size.x = size;
 
  194                         buffer_.volume_size.y = size;
 
  195                         buffer_.volume_size.z = size;
 
  204                   void computeAndSetNewCubeMetricOrigin (cv::Ptr<cuda::TsdfVolume> volume, 
const cv::Vec3f& target_point, 
Vec3i& offset);
 
  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);
 
  214                         buffer_.tsdf_rolling_buff_origin = buffer_.tsdf_memory_start;
 
  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);
 
  249                   int slice_count_ = 0;
 
  260                                 return f < 0 ? f-.5:f+.5;
 
  263                   float euclideanDistance(
const Point& p1, 
const Point& p2);
 
  265                   void getEulerYPR(
float& yaw, 
float& pitch, 
float& roll, cv::Affine3<float>::Mat3& mat,  
unsigned int solution_number = 1);
 
  302                         CudaData localVolume = tsdf_volume->data();
 
  317 #endif // CYCLICAL_BUFFER_IMPL_H_