Public Member Functions | Private Member Functions | Private Attributes | List of all members
kfusion::cuda::CyclicalBuffer Class Reference

CyclicalBuffer implements a cyclical TSDF buffer. The class offers a simple interface, by handling shifts and maintaining the world autonomously. More...

#include <cyclical_buffer.h>

Public Member Functions

void addImgPose (ImgPose *imgPose)
 
bool checkForShift (cv::Ptr< cuda::TsdfVolume > volume, const Affine3f &cam_pose, const double distance_camera_target, const bool perform_shift=true, const bool last_shift=false, const bool record_mode=false)
 Check if shifting needs to be performed, returns true if so. Shifting is considered needed if the target point is farther than distance_treshold_. The target point is located at distance_camera_point on the local Z axis of the camera. More...
 
void computeAndSetNewCubeMetricOrigin (cv::Ptr< cuda::TsdfVolume > volume, const cv::Vec3f &target_point, Vec3i &offset)
 Computes and set the origin of the new cube (relative to the world), centered around a the target point. More...
 
 CyclicalBuffer (KinFuParams params)
 Constructor for a cubic CyclicalBuffer. More...
 
tsdf_buffergetBuffer ()
 get a pointer to the tsdf_buffer structure. More...
 
float getDistanceThreshold ()
 Returns the distance threshold between cube's center and target point that triggers a shift. More...
 
MeshPtr getMesh ()
 
Vec3f getOrigin ()
 
int getSliceCount ()
 
void initBuffer (cv::Ptr< cuda::TsdfVolume > tsdf_volume)
 Initializes memory pointers of the cyclical buffer (start, end, current origin) More...
 
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)
 Perform shifting operations: Compute offsets. Extract current slice from TSDF buffer. Extract existing data from world. Clear shifted slice in TSDF buffer. Push existing data into TSDF buffer. Update rolling buffer Update world model. More...
 
void resetBuffer (cv::Ptr< cuda::TsdfVolume > tsdf_volume)
 Reset buffer structure. More...
 
void resetMesh ()
 
void setDistanceThreshold (const double threshold)
 Sets the distance threshold between cube's center and target point that triggers a shift. More...
 
void setVolumeSize (const double size)
 Set the physical size represented by the default TSDF volume. More...
 
void setVolumeSize (const Vec3f size)
 Set the physical size represented by the default TSDF volume. More...
 
void setVoxelSize (const Vec3f vsize)
 
 ~CyclicalBuffer ()
 Constructor for a non-cubic CyclicalBuffer. More...
 

Private Member Functions

void calcBounds (Vec3i &offset, Vec3i &minBounds, Vec3i &maxBounds)
 
int calcIndex (float f) const
 
float euclideanDistance (const Point &p1, const Point &p2)
 
void getEulerYPR (float &yaw, float &pitch, float &roll, cv::Affine3< float >::Mat3 &mat, unsigned int solution_number=1)
 
void shiftOrigin (cv::Ptr< cuda::TsdfVolume > tsdf_volume, Vec3i offset)
 updates cyclical buffer origins given offsets on X, Y and Z More...
 

Private Attributes

tsdf_buffer buffer_
 structure that contains all TSDF buffer's addresses More...
 
DeviceArray< Pointcloud_buffer_device_
 buffer used to extract XYZ values from GPU More...
 
cv::Mat cloud_slice_
 
double distance_threshold_
 distance threshold (cube's center to target point) to trigger shift More...
 
Vec3i global_shift_
 
std::vector< ImgPose * > imgPoses_
 
Affine3f last_camPose_
 
bool no_reconstruct_
 
bool optimize_
 
LVRPipeline pl_
 
int slice_count_ = 0
 

Detailed Description

CyclicalBuffer implements a cyclical TSDF buffer. The class offers a simple interface, by handling shifts and maintaining the world autonomously.

Author
Raphael Favier, Francisco Heredia

Definition at line 64 of file cyclical_buffer.h.

Constructor & Destructor Documentation

◆ CyclicalBuffer()

kfusion::cuda::CyclicalBuffer::CyclicalBuffer ( KinFuParams  params)
inline

Constructor for a cubic CyclicalBuffer.

Parameters
[in]distance_thresholddistance between cube center and target point at which we decide to shift.
[in]cube_sizephysical size (in meters) of the volume (here, a cube) represented by the TSDF buffer.
[in]nb_voxels_per_axisnumber of voxels per axis of the volume represented by the TSDF buffer.

Definition at line 73 of file cyclical_buffer.h.

◆ ~CyclicalBuffer()

kfusion::cuda::CyclicalBuffer::~CyclicalBuffer ( )
inline

Constructor for a non-cubic CyclicalBuffer.

Parameters
[in]distance_thresholddistance between cube center and target point at which we decide to shift.
[in]volume_size_xphysical size (in meters) of the volume, X axis.
[in]volume_size_yphysical size (in meters) of the volume, Y axis.
[in]volume_size_zphysical size (in meters) of the volume, Z axis.
[in]nb_voxels_xnumber of voxels for X axis of the volume represented by the TSDF buffer.
[in]nb_voxels_ynumber of voxels for Y axis of the volume represented by the TSDF buffer.
[in]nb_voxels_znumber of voxels for Z axis of the volume represented by the TSDF buffer.

Definition at line 112 of file cyclical_buffer.h.

Member Function Documentation

◆ addImgPose()

void kfusion::cuda::CyclicalBuffer::addImgPose ( ImgPose imgPose)
inline

Definition at line 232 of file cyclical_buffer.h.

◆ calcBounds()

void kfusion::cuda::CyclicalBuffer::calcBounds ( Vec3i offset,
Vec3i minBounds,
Vec3i maxBounds 
)
private

Definition at line 171 of file cyclical_buffer.cpp.

◆ calcIndex()

int kfusion::cuda::CyclicalBuffer::calcIndex ( float  f) const
inlineprivate

Definition at line 258 of file cyclical_buffer.h.

◆ checkForShift()

bool kfusion::cuda::CyclicalBuffer::checkForShift ( cv::Ptr< cuda::TsdfVolume volume,
const Affine3f cam_pose,
const double  distance_camera_target,
const bool  perform_shift = true,
const bool  last_shift = false,
const bool  record_mode = false 
)

Check if shifting needs to be performed, returns true if so. Shifting is considered needed if the target point is farther than distance_treshold_. The target point is located at distance_camera_point on the local Z axis of the camera.

Parameters
[in]volumepointer to the TSDFVolume living in GPU
[in]cam_poseglobal pose of the camera in the world
[in]distance_camera_targetdistance from the camera's origin to the target point
[in]perform_shiftif set to false, shifting is not performed. The function will return true if shifting is needed.
[in]last_shiftif set to true, the whole cube will be shifted. This is used to push the whole cube to the world model.
[in]force_shiftif set to true, shifting is forced.
Returns
true is the cube needs to be or has been shifted.

Definition at line 43 of file cyclical_buffer.cpp.

◆ computeAndSetNewCubeMetricOrigin()

void kfusion::cuda::CyclicalBuffer::computeAndSetNewCubeMetricOrigin ( cv::Ptr< cuda::TsdfVolume volume,
const cv::Vec3f &  target_point,
Vec3i offset 
)

Computes and set the origin of the new cube (relative to the world), centered around a the target point.

Parameters
[in]target_pointthe target point around which the new cube will be centered.
[out]shiftXshift on X axis (in indices).
[out]shiftYshift on Y axis (in indices).
[out]shiftZshift on Z axis (in indices).

Definition at line 150 of file cyclical_buffer.cpp.

◆ euclideanDistance()

float kfusion::cuda::CyclicalBuffer::euclideanDistance ( const Point p1,
const Point p2 
)
private

◆ getBuffer()

tsdf_buffer& kfusion::cuda::CyclicalBuffer::getBuffer ( )
inline

get a pointer to the tsdf_buffer structure.

Returns
a pointer to the tsdf_buffer used by cyclical buffer object.

Definition at line 162 of file cyclical_buffer.h.

◆ getDistanceThreshold()

float kfusion::cuda::CyclicalBuffer::getDistanceThreshold ( )
inline

Returns the distance threshold between cube's center and target point that triggers a shift.

Definition at line 157 of file cyclical_buffer.h.

◆ getEulerYPR()

void kfusion::cuda::CyclicalBuffer::getEulerYPR ( float &  yaw,
float &  pitch,
float &  roll,
cv::Affine3< float >::Mat3 &  mat,
unsigned int  solution_number = 1 
)
private

◆ getMesh()

MeshPtr kfusion::cuda::CyclicalBuffer::getMesh ( )
inline

Definition at line 234 of file cyclical_buffer.h.

◆ getOrigin()

Vec3f kfusion::cuda::CyclicalBuffer::getOrigin ( )
inline

Definition at line 183 of file cyclical_buffer.h.

◆ getSliceCount()

int kfusion::cuda::CyclicalBuffer::getSliceCount ( )
inline

Definition at line 236 of file cyclical_buffer.h.

◆ initBuffer()

void kfusion::cuda::CyclicalBuffer::initBuffer ( cv::Ptr< cuda::TsdfVolume tsdf_volume)
inline

Initializes memory pointers of the cyclical buffer (start, end, current origin)

Parameters
[in]tsdf_volumepointer to the TSDF volume managed by this cyclical buffer

Definition at line 209 of file cyclical_buffer.h.

◆ performShift()

void kfusion::cuda::CyclicalBuffer::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 
)

Perform shifting operations: Compute offsets. Extract current slice from TSDF buffer. Extract existing data from world. Clear shifted slice in TSDF buffer. Push existing data into TSDF buffer. Update rolling buffer Update world model.

Parameters
[in]volumepointer to the TSDFVolume living in GPU
[in]target_pointtarget point around which the new cube will be centered
[in]last_shiftif set to true, the whole cube will be shifted. This is used to push the whole cube to the world model.

Definition at line 71 of file cyclical_buffer.cpp.

◆ resetBuffer()

void kfusion::cuda::CyclicalBuffer::resetBuffer ( cv::Ptr< cuda::TsdfVolume tsdf_volume)
inline

Reset buffer structure.

Parameters
[in]tsdf_volumepointer to the TSDF volume managed by this cyclical buffer

Definition at line 220 of file cyclical_buffer.h.

◆ resetMesh()

void kfusion::cuda::CyclicalBuffer::resetMesh ( )
inline

Definition at line 231 of file cyclical_buffer.h.

◆ setDistanceThreshold()

void kfusion::cuda::CyclicalBuffer::setDistanceThreshold ( const double  threshold)
inline

Sets the distance threshold between cube's center and target point that triggers a shift.

Parameters
[in]thresholdthe distance in meters at which to trigger shift.

Definition at line 151 of file cyclical_buffer.h.

◆ setVolumeSize() [1/2]

void kfusion::cuda::CyclicalBuffer::setVolumeSize ( const double  size)
inline

Set the physical size represented by the default TSDF volume.

Parameters
[in]sizesize of the volume on all axis, in meters.

Definition at line 191 of file cyclical_buffer.h.

◆ setVolumeSize() [2/2]

void kfusion::cuda::CyclicalBuffer::setVolumeSize ( const Vec3f  size)
inline

Set the physical size represented by the default TSDF volume.

Parameters
[in]size_xsize of the volume on X axis, in meters.
[in]size_ysize of the volume on Y axis, in meters.
[in]size_zsize of the volume on Z axis, in meters.

Definition at line 169 of file cyclical_buffer.h.

◆ setVoxelSize()

void kfusion::cuda::CyclicalBuffer::setVoxelSize ( const Vec3f  vsize)
inline

Definition at line 176 of file cyclical_buffer.h.

◆ shiftOrigin()

void kfusion::cuda::CyclicalBuffer::shiftOrigin ( cv::Ptr< cuda::TsdfVolume tsdf_volume,
Vec3i  offset 
)
inlineprivate

updates cyclical buffer origins given offsets on X, Y and Z

Parameters
[in]tsdf_volumepointer to the TSDF volume managed by this cyclical buffer
[in]offset_xoffset in indices on axis X
[in]offset_yoffset in indices on axis Y
[in]offset_zoffset in indices on axis Z

Definition at line 275 of file cyclical_buffer.h.

Member Data Documentation

◆ buffer_

tsdf_buffer kfusion::cuda::CyclicalBuffer::buffer_
private

structure that contains all TSDF buffer's addresses

Definition at line 254 of file cyclical_buffer.h.

◆ cloud_buffer_device_

DeviceArray<Point> kfusion::cuda::CyclicalBuffer::cloud_buffer_device_
private

buffer used to extract XYZ values from GPU

Definition at line 242 of file cyclical_buffer.h.

◆ cloud_slice_

cv::Mat kfusion::cuda::CyclicalBuffer::cloud_slice_
private

Definition at line 247 of file cyclical_buffer.h.

◆ distance_threshold_

double kfusion::cuda::CyclicalBuffer::distance_threshold_
private

distance threshold (cube's center to target point) to trigger shift

Definition at line 245 of file cyclical_buffer.h.

◆ global_shift_

Vec3i kfusion::cuda::CyclicalBuffer::global_shift_
private

Definition at line 246 of file cyclical_buffer.h.

◆ imgPoses_

std::vector<ImgPose*> kfusion::cuda::CyclicalBuffer::imgPoses_
private

Definition at line 248 of file cyclical_buffer.h.

◆ last_camPose_

Affine3f kfusion::cuda::CyclicalBuffer::last_camPose_
private

Definition at line 250 of file cyclical_buffer.h.

◆ no_reconstruct_

bool kfusion::cuda::CyclicalBuffer::no_reconstruct_
private

Definition at line 251 of file cyclical_buffer.h.

◆ optimize_

bool kfusion::cuda::CyclicalBuffer::optimize_
private

Definition at line 251 of file cyclical_buffer.h.

◆ pl_

LVRPipeline kfusion::cuda::CyclicalBuffer::pl_
private

Definition at line 257 of file cyclical_buffer.h.

◆ slice_count_

int kfusion::cuda::CyclicalBuffer::slice_count_ = 0
private

Definition at line 249 of file cyclical_buffer.h.


The documentation for this class was generated from the following files:


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