mirror of
https://github.com/opencv/opencv_contrib.git
synced 2025-10-20 12:55:15 +08:00
KinectFusion big update: OpenCL support, etc. (#1798)
* KinFu demo: idle mode added * undistort added * KinFu demo: depth recorder added * TSDFVolume gets voxelSize, voxelSizeInv, truncDist members; decorative fixes * TSDFVolumeGPU::integrate(): host code compiles * TSDFVolume: truncDist fixed * TSDFVolume::integrate(): initial OCL version is done * TSDFVolume::integrate(): OCL: minor fixes * kinfu: small fixes * TSDFVolume::raycast(): initial GPU version is done * USE_INTRINSICS directive for centralized enable/disable opt. code * TSDF Volume supports 3 different sizes/resolutions on each dimension * TSDFVolume: serviceMembers moved to parent class * TSDFVolumeGPU: mem order changed, gave perf boost 4x * Frame: fixed UMat as InputArray; TSDF: comments, TODOs, minor fixes * Frame::getPointsNormals(); minors * FrameGPU: initial version (not working) * minor * FrameGPU: several fixes * added OCL "fast" options * ICP OCL: initial slow version is done (host-side reduce) * ICP OCL: reduce is done, buggy * KinFu Frame: more args fixes * ICP OCL: small fixes to kernel * ICP OCL reduce works * OCL code refactored * ICP OCL: less allocations, better speed * ICP OCL: pose matrix made arg * Render OCL: small fix * Demo: using UMats everywhere * TSDF integrate OCL: put const arg into kernel arg * Platform parameter partially removed, implementation choice is done through OCL availability check * Frame and FrameGenerator removed (other code is in following commits) * CPU render: 4b instead of 3b * ICP: no Frame class use, one class for both CPU and GPU code * demo: fix for UMat chain * TSDF: no Frame or FrameGenerator use * KinFu: no Frame or FrameGenerator, parametrized for Mat or UMat based on OCL availability * KinFu::setParams() removed since it has no effect anyway * TSDF::raycast OCL: fixed normals rendering * ScopeTime -> CV_TRACE * 3-dims resolution and size passed to API * fixed unexpected fails of ICP OCL * voxels made cubic again * args fixed a little * fixed volSize calculation * Tests: inequal, OCL, unified scene test function * kinfu_frame: input types fixed * fixed for Intel HD Graphics * KinFu demo: setUseOptimized instead of setUseOpenCL * tsdf: data types fixed * TSDF OCL: fetch normals implemented * roundDownPow2 -> utils.hpp * TSDF OCL: fetch points+normals implemented * TSDF OCL: NoSize, other fixes for kernel args * Frame OCL: HAVE_OPENCL, NoSize, other kernel args fixed * ICP OCL: HAVE_OPENCL, NoSize and other kernel fixes * KinFu demo fixes: volume size and too long delay * whitespace fix * TSDF: allowed sizes not divisable by 32 * TSDF: fixed type traits; added optimization TODOs * KinFu made non-free * minor fixes: cast and whitespace * fixed FastICP test * warnings fixed: implicit type conversions * OCL kernels: local args made through KernelArg::Local(lsz) call * MSVC warnings fixed * a workaround for broken OCV's bilateral * KinFu tests made a bit faster * build fixed until 3.4 isn't merged to master * warnings fixed, test time shortened
This commit is contained in:

committed by
Vadim Pisarevsky

parent
2f014f6f40
commit
75bcd397af
@@ -28,19 +28,6 @@ struct CV_EXPORTS_W Params
|
||||
*/
|
||||
CV_WRAP static Ptr<Params> coarseParams();
|
||||
|
||||
enum PlatformType
|
||||
{
|
||||
|
||||
PLATFORM_CPU, PLATFORM_GPU
|
||||
};
|
||||
|
||||
/** @brief A platform on which to run the algorithm.
|
||||
*
|
||||
Currently KinFu supports only one platform which is a CPU.
|
||||
GPU platform is to be implemented in the future.
|
||||
*/
|
||||
PlatformType platform;
|
||||
|
||||
/** @brief frame size in pixels */
|
||||
CV_PROP_RW Size frameSize;
|
||||
|
||||
@@ -50,8 +37,9 @@ struct CV_EXPORTS_W Params
|
||||
/** @brief pre-scale per 1 meter for input values
|
||||
|
||||
Typical values are:
|
||||
* 5000 per 1 meter for the 16-bit PNG files of TUM database
|
||||
* 1 per 1 meter for the 32-bit float images in the ROS bag files
|
||||
* 5000 per 1 meter for the 16-bit PNG files of TUM database
|
||||
* 1000 per 1 meter for Kinect 2 device
|
||||
* 1 per 1 meter for the 32-bit float images in the ROS bag files
|
||||
*/
|
||||
CV_PROP_RW float depthFactor;
|
||||
|
||||
@@ -65,13 +53,13 @@ struct CV_EXPORTS_W Params
|
||||
/** @brief Number of pyramid levels for ICP */
|
||||
CV_PROP_RW int pyramidLevels;
|
||||
|
||||
/** @brief Resolution of voxel cube
|
||||
/** @brief Resolution of voxel space
|
||||
|
||||
Number of voxels in each cube edge.
|
||||
Number of voxels in each dimension.
|
||||
*/
|
||||
CV_PROP_RW int volumeDims;
|
||||
/** @brief Size of voxel cube side in meters */
|
||||
CV_PROP_RW float volumeSize;
|
||||
CV_PROP_RW Vec3i volumeDims;
|
||||
/** @brief Size of voxel in meters */
|
||||
CV_PROP_RW float voxelSize;
|
||||
|
||||
/** @brief Minimal camera movement in meters
|
||||
|
||||
@@ -84,7 +72,7 @@ struct CV_EXPORTS_W Params
|
||||
|
||||
/** @brief distance to truncate in meters
|
||||
|
||||
Distances that exceed this value will be truncated in voxel cube values.
|
||||
Distances to surface that exceed this value will be truncated to 1.0.
|
||||
*/
|
||||
CV_PROP_RW float tsdf_trunc_dist;
|
||||
|
||||
@@ -128,11 +116,19 @@ struct CV_EXPORTS_W Params
|
||||
The output can be obtained as a vector of points and their normals
|
||||
or can be Phong-rendered from given camera pose.
|
||||
|
||||
An internal representation of a model is a voxel cube that keeps TSDF values
|
||||
An internal representation of a model is a voxel cuboid that keeps TSDF values
|
||||
which are a sort of distances to the surface (for details read the @cite kinectfusion article about TSDF).
|
||||
There is no interface to that representation yet.
|
||||
|
||||
This implementation is based on (kinfu-remake)[https://github.com/Nerei/kinfu_remake].
|
||||
KinFu uses OpenCL acceleration automatically if available.
|
||||
To enable or disable it explicitly use cv::setUseOptimized() or cv::ocl::setUseOpenCL().
|
||||
|
||||
This implementation is based on [kinfu-remake](https://github.com/Nerei/kinfu_remake).
|
||||
|
||||
Note that the KinectFusion algorithm was patented and its use may be restricted by
|
||||
the list of patents mentioned in README.md file in this module directory.
|
||||
|
||||
That's why you need to set the OPENCV_ENABLE_NONFREE option in CMake to use KinectFusion.
|
||||
*/
|
||||
class CV_EXPORTS_W KinFu
|
||||
{
|
||||
@@ -142,11 +138,10 @@ public:
|
||||
|
||||
/** @brief Get current parameters */
|
||||
virtual const Params& getParams() const = 0;
|
||||
virtual void setParams(const Params&) = 0;
|
||||
|
||||
/** @brief Renders a volume into an image
|
||||
|
||||
Renders a 0-surface of TSDF using Phong shading into a CV_8UC3 Mat.
|
||||
Renders a 0-surface of TSDF using Phong shading into a CV_8UC4 Mat.
|
||||
Light pose is fixed in KinFu params.
|
||||
|
||||
@param image resulting image
|
||||
@@ -186,21 +181,18 @@ public:
|
||||
*/
|
||||
CV_WRAP virtual void reset() = 0;
|
||||
|
||||
/** @brief Get current pose in voxel cube space */
|
||||
/** @brief Get current pose in voxel space */
|
||||
virtual const Affine3f getPose() const = 0;
|
||||
|
||||
/** @brief Process next depth frame
|
||||
|
||||
Integrates depth into voxel cube with respect to its ICP-calculated pose.
|
||||
Integrates depth into voxel space with respect to its ICP-calculated pose.
|
||||
Input image is converted to CV_32F internally if has another type.
|
||||
|
||||
@param depth one-channel image which size and depth scale is described in algorithm's parameters
|
||||
@return true if succeded to align new frame with current scene, false if opposite
|
||||
*/
|
||||
CV_WRAP virtual bool update(InputArray depth) = 0;
|
||||
|
||||
private:
|
||||
class KinFuImpl;
|
||||
};
|
||||
|
||||
//! @}
|
||||
|
Reference in New Issue
Block a user