KinfuTracker class encapsulates implementation of Microsoft Kinect Fusion algorithm.
More...
#include </builddir/build/BUILD/pcl-1.12.0/gpu/kinfu/include/pcl/gpu/kinfu/kinfu.h>
|
| KinfuTracker (int rows=480, int cols=640) |
| Constructor.
|
|
void | setDepthIntrinsics (float fx, float fy, float cx=-1, float cy=-1) |
| Sets Depth camera intrinsics.
|
|
void | getDepthIntrinsics (float &fx, float &fy, float &cx, float &cy) const |
| Get Depth camera intrinsics.
|
|
void | setInitalCameraPose (const Eigen::Affine3f &pose) |
| Sets initial camera pose relative to volume coordinate space.
|
|
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.
|
|
void | setIcpCorespFilteringParams (float distThreshold, float sineOfAngle) |
| Sets ICP filtering parameters.
|
|
void | setCameraMovementThreshold (float threshold=0.001f) |
| Sets integration threshold.
|
|
void | initColorIntegration (int max_weight=-1) |
| Performs initialization for color integration.
|
|
int | cols () |
| Returns cols passed to ctor.
|
|
int | rows () |
| Returns rows passed to ctor.
|
|
bool | operator() (const DepthMap &depth, Eigen::Affine3f *hint=nullptr) |
| Processes next frame.
|
|
bool | operator() (const DepthMap &depth, const View &colors) |
| Processes next frame (both depth and color integration).
|
|
Eigen::Affine3f | getCameraPose (int time=-1) const |
| Returns camera pose at given time, default the last pose.
|
|
std::size_t | getNumberOfPoses () const |
| Returns number of poses including initial.
|
|
const TsdfVolume & | volume () const |
| Returns TSDF volume storage.
|
|
TsdfVolume & | volume () |
| Returns TSDF volume storage.
|
|
const ColorVolume & | colorVolume () const |
| Returns color volume storage.
|
|
ColorVolume & | colorVolume () |
| Returns color volume storage.
|
|
void | getImage (View &view) const |
| Renders 3D scene to display to human.
|
|
void | getLastFrameCloud (DeviceArray2D< PointType > &cloud) const |
| Returns point cloud abserved from last camera pose.
|
|
void | getLastFrameNormals (DeviceArray2D< NormalType > &normals) const |
| Returns point cloud abserved from last camera pose.
|
|
void | disableIcp () |
| Disables ICP forever.
|
|
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 67 of file kinfu.h.
◆ DepthMap
◆ NormalType
◆ PixelRGB
Pixel type for rendered image.
Definition at line 71 of file kinfu.h.
◆ PointType
◆ View
◆ KinfuTracker()
pcl::gpu::KinfuTracker::KinfuTracker |
( |
int | rows = 480, |
|
|
int | cols = 640 ) |
Constructor.
- Parameters
-
[in] | rows | height of depth image |
[in] | cols | width of depth image |
◆ colorVolume() [1/2]
Returns color volume storage.
◆ colorVolume() [2/2]
Returns color volume storage.
◆ cols()
int pcl::gpu::KinfuTracker::cols |
( |
| ) |
|
Returns cols passed to ctor.
◆ disableIcp()
void pcl::gpu::KinfuTracker::disableIcp |
( |
| ) |
|
◆ getCameraPose()
Eigen::Affine3f pcl::gpu::KinfuTracker::getCameraPose |
( |
int | time = -1 | ) |
const |
Returns camera pose at given time, default the last pose.
- Parameters
-
[in] | time | Index of frame for which camera pose is returned. |
- Returns
- camera pose
◆ getDepthIntrinsics()
Get Depth camera intrinsics.
- Parameters
-
[out] | fx | focal length x |
[out] | fy | focal length y |
[out] | cx | principal point x |
[out] | cy | principal point y |
◆ getImage()
void pcl::gpu::KinfuTracker::getImage |
( |
View & | view | ) |
const |
Renders 3D scene to display to human.
- Parameters
-
[out] | view | output array with image |
◆ getLastFrameCloud()
Returns point cloud abserved from last camera pose.
- Parameters
-
[out] | cloud | output array for points |
◆ getLastFrameNormals()
Returns point cloud abserved from last camera pose.
- Parameters
-
[out] | normals | output array for normals |
◆ getNumberOfPoses()
std::size_t pcl::gpu::KinfuTracker::getNumberOfPoses |
( |
| ) |
const |
Returns number of poses including initial.
◆ initColorIntegration()
void pcl::gpu::KinfuTracker::initColorIntegration |
( |
int | max_weight = -1 | ) |
|
Performs initialization for color integration.
Must be called before calling color integration.
- Parameters
-
[in] | max_weight | max weighe for color integration. -1 means default weight. |
◆ operator()() [1/2]
Processes next frame (both depth and color integration).
Please call initColorIntegration before invpoking this.
- Parameters
-
[in] | depth | next depth frame with values in millimeters |
[in] | colors | next RGB frame |
- Returns
- true if can render 3D view.
◆ operator()() [2/2]
Processes next frame.
- Parameters
-
[in] | depth | next frame with values in millimeters |
| hint | |
- Returns
- true if can render 3D view.
◆ rows()
int pcl::gpu::KinfuTracker::rows |
( |
| ) |
|
Returns rows passed to ctor.
◆ setCameraMovementThreshold()
void pcl::gpu::KinfuTracker::setCameraMovementThreshold |
( |
float | threshold = 0.001f | ) |
|
Sets integration threshold.
TSDF volume is integrated iff a camera movement metric exceedes the threshold value. The metric represents the following: M = (rodrigues(Rotation).norm() + alpha*translation.norm())/2, where alpha = 1.f (hardcoded constant)
- Parameters
-
[in] | threshold | a value to compare with the metric. Suitable values are ~0.001
|
◆ setDepthIntrinsics()
Sets Depth camera intrinsics.
- Parameters
-
[in] | fx | focal length x |
[in] | fy | focal length y |
[in] | cx | principal point x |
[in] | cy | principal point y |
◆ setDepthTruncationForICP()
void pcl::gpu::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_distance | Maximal distance, higher values are reset to zero (means no measurement). |
◆ setIcpCorespFilteringParams()
void pcl::gpu::KinfuTracker::setIcpCorespFilteringParams |
( |
float | distThreshold, |
|
|
float | sineOfAngle ) |
Sets ICP filtering parameters.
- Parameters
-
[in] | distThreshold | distance. |
[in] | sineOfAngle | sine of angle between normals. |
◆ setInitalCameraPose()
void pcl::gpu::KinfuTracker::setInitalCameraPose |
( |
const Eigen::Affine3f & | pose | ) |
|
Sets initial camera pose relative to volume coordinate space.
- Parameters
-
[in] | pose | Initial camera pose |
◆ volume() [1/2]
Returns TSDF volume storage.
◆ volume() [2/2]
Returns TSDF volume storage.
The documentation for this class was generated from the following file:
- /builddir/build/BUILD/pcl-1.12.0/gpu/kinfu/include/pcl/gpu/kinfu/kinfu.h