Point Cloud Library (PCL)  1.14.1-dev
List of all members | Public Types | Public Member Functions
pcl::gpu::kinfuLS::KinfuTracker Class Reference

KinfuTracker class encapsulates implementation of Microsoft Kinect Fusion algorithm. More...

#include </__w/1/s/gpu/kinfu_large_scale/include/pcl/gpu/kinfu_large_scale/kinfu.h>

Public Types

using PixelRGB = pcl::gpu::kinfuLS::PixelRGB
 Pixel type for rendered image. More...
 
using View = DeviceArray2D< PixelRGB >
 
using DepthMap = DeviceArray2D< unsigned short >
 
using PointType = pcl::PointXYZ
 
using NormalType = pcl::Normal
 

Public Member Functions

void performLastScan ()
 
bool isFinished ()
 
 KinfuTracker (const Eigen::Vector3f &volumeSize, const float shiftingDistance, int rows=480, int cols=640)
 Constructor. More...
 
void setDepthIntrinsics (float fx, float fy, float cx=-1, float cy=-1)
 Sets Depth camera intrinsics. More...
 
void setInitialCameraPose (const Eigen::Affine3f &pose)
 Sets initial camera pose relative to volume coordinate space. More...
 
void setDepthTruncationForICP (float max_icp_distance=0.f)
 Sets truncation threshold for depth image for ICP step only! This helps to filter measurements that are outside tsdf volume. More...
 
void setIcpCorespFilteringParams (float distThreshold, float sineOfAngle)
 Sets ICP filtering parameters. More...
 
void setCameraMovementThreshold (float threshold=0.001f)
 Sets integration threshold. More...
 
void initColorIntegration (int max_weight=-1)
 Performs initialization for color integration. More...
 
int cols ()
 Returns cols passed to ctor. More...
 
int rows ()
 Returns rows passed to ctor. More...
 
bool operator() (const DepthMap &depth)
 Processes next frame. More...
 
bool operator() (const DepthMap &depth, const View &colors)
 Processes next frame (both depth and color integration). More...
 
Eigen::Affine3f getCameraPose (int time=-1) const
 Returns camera pose at given time, default the last pose. More...
 
Eigen::Affine3f getLastEstimatedPose () const
 
std::size_t getNumberOfPoses () const
 Returns number of poses including initial. More...
 
const TsdfVolumevolume () const
 Returns TSDF volume storage. More...
 
TsdfVolumevolume ()
 Returns TSDF volume storage. More...
 
const ColorVolumecolorVolume () const
 Returns color volume storage. More...
 
ColorVolumecolorVolume ()
 Returns color volume storage. More...
 
void getImage (View &view) const
 Renders 3D scene to display to human. More...
 
void getLastFrameCloud (DeviceArray2D< PointType > &cloud) const
 Returns point cloud abserved from last camera pose. More...
 
void getLastFrameNormals (DeviceArray2D< NormalType > &normals) const
 Returns point cloud abserved from last camera pose. More...
 
tsdf_buffergetCyclicalBufferStructure ()
 Returns pointer to the cyclical buffer structure. More...
 
void extractAndSaveWorld ()
 Extract the world and save it. More...
 
bool icpIsLost ()
 Returns true if ICP is currently lost. More...
 
void reset ()
 Performs the tracker reset to initial state. More...
 
void setDisableICP ()
 
bool hasShifted () const
 Return whether the last update resulted in a shift. More...
 

Detailed Description

KinfuTracker class encapsulates implementation of Microsoft Kinect Fusion algorithm.

Author
Anatoly Baskeheev, Itseez Ltd, (mynam.nosp@m.e.my.nosp@m.surna.nosp@m.me@m.nosp@m.ycomp.nosp@m.any..nosp@m.com)

Definition at line 71 of file kinfu.h.

Member Typedef Documentation

◆ DepthMap

Definition at line 79 of file kinfu.h.

◆ NormalType

Definition at line 82 of file kinfu.h.

◆ PixelRGB

Pixel type for rendered image.

Definition at line 76 of file kinfu.h.

◆ PointType

Definition at line 81 of file kinfu.h.

◆ View

Definition at line 78 of file kinfu.h.

Constructor & Destructor Documentation

◆ KinfuTracker()

pcl::gpu::kinfuLS::KinfuTracker::KinfuTracker ( const Eigen::Vector3f &  volumeSize,
const float  shiftingDistance,
int  rows = 480,
int  cols = 640 
)

Constructor.

Parameters
[in]volumeSizephysical size of the volume represented by the tdsf volume. In meters.
[in]shiftingDistancewhen the camera target point is farther than shiftingDistance from the center of the volume, shiting occurs. In meters.
Note
The target point is located at (0, 0, 0.6*volumeSize) in camera coordinates.
Parameters
[in]rowsheight of depth image
[in]colswidth of depth image

Member Function Documentation

◆ colorVolume() [1/2]

ColorVolume& pcl::gpu::kinfuLS::KinfuTracker::colorVolume ( )

Returns color volume storage.

◆ colorVolume() [2/2]

const ColorVolume& pcl::gpu::kinfuLS::KinfuTracker::colorVolume ( ) const

Returns color volume storage.

◆ cols()

int pcl::gpu::kinfuLS::KinfuTracker::cols ( )

Returns cols passed to ctor.

◆ extractAndSaveWorld()

void pcl::gpu::kinfuLS::KinfuTracker::extractAndSaveWorld ( )

Extract the world and save it.

◆ getCameraPose()

Eigen::Affine3f pcl::gpu::kinfuLS::KinfuTracker::getCameraPose ( int  time = -1) const

Returns camera pose at given time, default the last pose.

Parameters
[in]timeIndex of frame for which camera pose is returned.
Returns
camera pose

◆ getCyclicalBufferStructure()

tsdf_buffer* pcl::gpu::kinfuLS::KinfuTracker::getCyclicalBufferStructure ( )
inline

Returns pointer to the cyclical buffer structure.

Definition at line 210 of file kinfu.h.

◆ getImage()

void pcl::gpu::kinfuLS::KinfuTracker::getImage ( View view) const

Renders 3D scene to display to human.

Parameters
[out]viewoutput array with image

◆ getLastEstimatedPose()

Eigen::Affine3f pcl::gpu::kinfuLS::KinfuTracker::getLastEstimatedPose ( ) const

◆ getLastFrameCloud()

void pcl::gpu::kinfuLS::KinfuTracker::getLastFrameCloud ( DeviceArray2D< PointType > &  cloud) const

Returns point cloud abserved from last camera pose.

Parameters
[out]cloudoutput array for points

◆ getLastFrameNormals()

void pcl::gpu::kinfuLS::KinfuTracker::getLastFrameNormals ( DeviceArray2D< NormalType > &  normals) const

Returns point cloud abserved from last camera pose.

Parameters
[out]normalsoutput array for normals

◆ getNumberOfPoses()

std::size_t pcl::gpu::kinfuLS::KinfuTracker::getNumberOfPoses ( ) const

Returns number of poses including initial.

◆ hasShifted()

bool pcl::gpu::kinfuLS::KinfuTracker::hasShifted ( ) const
inline

Return whether the last update resulted in a shift.

Definition at line 240 of file kinfu.h.

◆ icpIsLost()

bool pcl::gpu::kinfuLS::KinfuTracker::icpIsLost ( )
inline

Returns true if ICP is currently lost.

Definition at line 222 of file kinfu.h.

◆ initColorIntegration()

void pcl::gpu::kinfuLS::KinfuTracker::initColorIntegration ( int  max_weight = -1)

Performs initialization for color integration.

Must be called before calling color integration.

Parameters
[in]max_weightmax weighe for color integration. -1 means default weight.

◆ isFinished()

bool pcl::gpu::kinfuLS::KinfuTracker::isFinished ( )
inline

Definition at line 88 of file kinfu.h.

◆ operator()() [1/2]

bool pcl::gpu::kinfuLS::KinfuTracker::operator() ( const DepthMap depth)

Processes next frame.

Parameters
[in]depthnext frame with values in millimeters
Returns
true if can render 3D view.

◆ operator()() [2/2]

bool pcl::gpu::kinfuLS::KinfuTracker::operator() ( const DepthMap depth,
const View colors 
)

Processes next frame (both depth and color integration).

Please call initColorIntegration before invpoking this.

Parameters
[in]depthnext depth frame with values in millimeters
[in]colorsnext RGB frame
Returns
true if can render 3D view.

◆ performLastScan()

void pcl::gpu::kinfuLS::KinfuTracker::performLastScan ( )
inline

Definition at line 85 of file kinfu.h.

◆ reset()

void pcl::gpu::kinfuLS::KinfuTracker::reset ( )

Performs the tracker reset to initial state.

It's used if camera tracking fails.

◆ rows()

int pcl::gpu::kinfuLS::KinfuTracker::rows ( )

Returns rows passed to ctor.

◆ setCameraMovementThreshold()

void pcl::gpu::kinfuLS::KinfuTracker::setCameraMovementThreshold ( float  threshold = 0.001f)

Sets integration threshold.

TSDF volume is integrated iff a camera movement metric exceeds the threshold value. The metric represents the following: M = (rodrigues(Rotation).norm() + alpha*translation.norm())/2, where alpha = 1.f (hardcoded constant)

Parameters
[in]thresholda value to compare with the metric. Suitable values are ~0.001

◆ setDepthIntrinsics()

void pcl::gpu::kinfuLS::KinfuTracker::setDepthIntrinsics ( float  fx,
float  fy,
float  cx = -1,
float  cy = -1 
)

Sets Depth camera intrinsics.

Parameters
[in]fxfocal length x
[in]fyfocal length y
[in]cxprincipal point x
[in]cyprincipal point y

◆ setDepthTruncationForICP()

void pcl::gpu::kinfuLS::KinfuTracker::setDepthTruncationForICP ( float  max_icp_distance = 0.f)

Sets truncation threshold for depth image for ICP step only! This helps to filter measurements that are outside tsdf volume.

Pass zero to disable the truncation.

Parameters
[in]max_icp_distanceMaximal distance, higher values are reset to zero (means no measurement).

◆ setDisableICP()

void pcl::gpu::kinfuLS::KinfuTracker::setDisableICP ( )
inline

Definition at line 232 of file kinfu.h.

◆ setIcpCorespFilteringParams()

void pcl::gpu::kinfuLS::KinfuTracker::setIcpCorespFilteringParams ( float  distThreshold,
float  sineOfAngle 
)

Sets ICP filtering parameters.

Parameters
[in]distThresholddistance.
[in]sineOfAnglesine of angle between normals.

◆ setInitialCameraPose()

void pcl::gpu::kinfuLS::KinfuTracker::setInitialCameraPose ( const Eigen::Affine3f &  pose)

Sets initial camera pose relative to volume coordinate space.

Parameters
[in]poseInitial camera pose

◆ volume() [1/2]

TsdfVolume& pcl::gpu::kinfuLS::KinfuTracker::volume ( )

Returns TSDF volume storage.

◆ volume() [2/2]

const TsdfVolume& pcl::gpu::kinfuLS::KinfuTracker::volume ( ) const

Returns TSDF volume storage.


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