large_kinfu.hpp 5.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147
  1. // This file is part of OpenCV project.
  2. // It is subject to the license terms in the LICENSE file found in the top-level directory
  3. // of this distribution and at http://opencv.org/license.html
  4. // This code is also subject to the license terms in the LICENSE_KinectFusion.md file found in this
  5. // module's directory
  6. #ifndef __OPENCV_RGBD_LARGEKINFU_HPP__
  7. #define __OPENCV_RGBD_LARGEKINFU_HPP__
  8. #include <opencv2/rgbd/volume.hpp>
  9. #include "opencv2/core.hpp"
  10. #include "opencv2/core/affine.hpp"
  11. namespace cv
  12. {
  13. namespace large_kinfu
  14. {
  15. struct CV_EXPORTS_W Params
  16. {
  17. /** @brief Default parameters
  18. A set of parameters which provides better model quality, can be very slow.
  19. */
  20. CV_WRAP static Ptr<Params> defaultParams();
  21. /** @brief Coarse parameters
  22. A set of parameters which provides better speed, can fail to match frames
  23. in case of rapid sensor motion.
  24. */
  25. CV_WRAP static Ptr<Params> coarseParams();
  26. /** @brief HashTSDF parameters
  27. A set of parameters suitable for use with HashTSDFVolume
  28. */
  29. CV_WRAP static Ptr<Params> hashTSDFParams(bool isCoarse);
  30. /** @brief frame size in pixels */
  31. CV_PROP_RW Size frameSize;
  32. /** @brief camera intrinsics */
  33. CV_PROP_RW Matx33f intr;
  34. /** @brief rgb camera intrinsics */
  35. CV_PROP_RW Matx33f rgb_intr;
  36. /** @brief pre-scale per 1 meter for input values
  37. Typical values are:
  38. * 5000 per 1 meter for the 16-bit PNG files of TUM database
  39. * 1000 per 1 meter for Kinect 2 device
  40. * 1 per 1 meter for the 32-bit float images in the ROS bag files
  41. */
  42. CV_PROP_RW float depthFactor;
  43. /** @brief Depth sigma in meters for bilateral smooth */
  44. CV_PROP_RW float bilateral_sigma_depth;
  45. /** @brief Spatial sigma in pixels for bilateral smooth */
  46. CV_PROP_RW float bilateral_sigma_spatial;
  47. /** @brief Kernel size in pixels for bilateral smooth */
  48. CV_PROP_RW int bilateral_kernel_size;
  49. /** @brief Number of pyramid levels for ICP */
  50. CV_PROP_RW int pyramidLevels;
  51. /** @brief Minimal camera movement in meters
  52. Integrate new depth frame only if camera movement exceeds this value.
  53. */
  54. CV_PROP_RW float tsdf_min_camera_movement;
  55. /** @brief light pose for rendering in meters */
  56. CV_PROP_RW Vec3f lightPose;
  57. /** @brief distance theshold for ICP in meters */
  58. CV_PROP_RW float icpDistThresh;
  59. /** @brief angle threshold for ICP in radians */
  60. CV_PROP_RW float icpAngleThresh;
  61. /** @brief number of ICP iterations for each pyramid level */
  62. CV_PROP_RW std::vector<int> icpIterations;
  63. /** @brief Threshold for depth truncation in meters
  64. All depth values beyond this threshold will be set to zero
  65. */
  66. CV_PROP_RW float truncateThreshold;
  67. /** @brief Volume parameters
  68. */
  69. kinfu::VolumeParams volumeParams;
  70. };
  71. /** @brief Large Scale Dense Depth Fusion implementation
  72. This class implements a 3d reconstruction algorithm for larger environments using
  73. Spatially hashed TSDF volume "Submaps".
  74. It also runs a periodic posegraph optimization to minimize drift in tracking over long sequences.
  75. Currently the algorithm does not implement a relocalization or loop closure module.
  76. Potentially a Bag of words implementation or RGBD relocalization as described in
  77. Glocker et al. ISMAR 2013 will be implemented
  78. It takes a sequence of depth images taken from depth sensor
  79. (or any depth images source such as stereo camera matching algorithm or even raymarching
  80. renderer). The output can be obtained as a vector of points and their normals or can be
  81. Phong-rendered from given camera pose.
  82. An internal representation of a model is a spatially hashed voxel cube that stores TSDF values
  83. which represent the distance to the closest surface (for details read the @cite kinectfusion article
  84. about TSDF). There is no interface to that representation yet.
  85. For posegraph optimization, a Submap abstraction over the Volume class is created.
  86. New submaps are added to the model when there is low visibility overlap between current viewing frustrum
  87. and the existing volume/model. Multiple submaps are simultaneously tracked and a posegraph is created and
  88. optimized periodically.
  89. LargeKinfu does not use any OpenCL acceleration yet.
  90. To enable or disable it explicitly use cv::setUseOptimized() or cv::ocl::setUseOpenCL().
  91. This implementation is inspired from Kintinuous, InfiniTAM and other SOTA algorithms
  92. You need to set the OPENCV_ENABLE_NONFREE option in CMake to use KinectFusion.
  93. */
  94. class CV_EXPORTS_W LargeKinfu
  95. {
  96. public:
  97. CV_WRAP static Ptr<LargeKinfu> create(const Ptr<Params>& _params);
  98. virtual ~LargeKinfu() = default;
  99. virtual const Params& getParams() const = 0;
  100. CV_WRAP virtual void render(OutputArray image) const = 0;
  101. CV_WRAP virtual void render(OutputArray image, const Matx44f& cameraPose) const = 0;
  102. CV_WRAP virtual void getCloud(OutputArray points, OutputArray normals) const = 0;
  103. CV_WRAP virtual void getPoints(OutputArray points) const = 0;
  104. CV_WRAP virtual void getNormals(InputArray points, OutputArray normals) const = 0;
  105. CV_WRAP virtual void reset() = 0;
  106. virtual const Affine3f getPose() const = 0;
  107. CV_WRAP virtual bool update(InputArray depth) = 0;
  108. };
  109. } // namespace large_kinfu
  110. } // namespace cv
  111. #endif