Skip to content

Commit 7022f4e

Browse files
Merge pull request #2619 from akashsharma02:submap
[GSoC] Add Submaps and PoseGraph optimization for Large Scale Depth Fusion * - Add HashTSDF class - Implement Integrate function (untested) * Integration seems to be working, raycasting does not * Update integration code * Integration and Raycasting fixes, (both work now) * - Format code - Clean up comments and few fixes * Add Kinect Fusion backup file * - Add interpolation for vertices and normals (slow and unreliable!) - Format code - Delete kinfu_back.cpp * Bug fix for integration and noisy odometry * - Create volume abstract class - Address Review comments * - Add getPoints and getNormals function - Fix formatting according to comments - Move volume abstract class to include/opencv2/rgbd/ - Write factory method for creating TSDFVolumes - Small bug fixes - Minor fixes according to comments * - Add tests for hashTSDF - Fix raycasting bug causing to loop forever - Suppress warnings by explicit conversion - Disable hashTsdf test until we figure out memory leak - style changes - Add missing license in a few files, correct precomp.hpp usage * - Use CRTP based static polymorphism to choose between CPU and GPU for HashTSDF volume * Create submap and submapMgr Implement overlap_ratio check to create new submaps * Early draft of posegraph and submaps (Doesn't even compile) * Minor cleanup (no compilation) * Track all submaps (no posegraph update yet) * Return inliers from ICP for weighting the constraints (Huber threshold based inliers pending) * Add updating constraints between submaps and retain same current map * Fix constraints creation between submaps and allow for switching between submaps * - Fix bug in allocate volumeUnits - Simplify calculation of visibleBlocks * Remove inlier calculation in fast_icp (not required) * Modify readFile to allow reading other datasets easily * - Implement posegraph update, Gauss newton is unstable - Minor changes to Gauss newton and Sparse matrix. Residual still increases slightly over iterations * Implement simplified levenberg marquardt * Bug fixes for Levenberg Marquardt and minor changes * minor changes * Fixes, but Optimizer is still not well behaved * Working Ceres optimizer * - Reorganize IO code for samples in a separate file - Minor fix for Ceres preprocessor definition - Remove unused generatorJacobian, will be used for opencv implementation of levenberg marquardt - Doxygen docs fix - Minor preprocessor fixes * - Reorganize IO code for samples in a separate file - Minor fix for Ceres preprocessor definition - Remove unused generatorJacobian, will be used for opencv implementation of levenberg marquardt - Doxygen docs fix - Minor preprocessor fixes - Move inline functions to header, and make function params const references * - Add Python bindings for volume struct - Remove makeVolume(const VolumeParams&) Python binding due to compilation issues - Minor changes according to comments * - Remove dynafu::Params() since it is identical to kinfu::Params() - Use common functions for dynafu_demo - Suppress "unreachable code" in volume.cpp * Minor API changes * Minor * Remove CRTP for HashTSDF class * Bug fixes for HashTSDF integration
1 parent ef0c722 commit 7022f4e

25 files changed

+2651
-841
lines changed

modules/rgbd/CMakeLists.txt

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,2 +1,11 @@
11
set(the_description "RGBD algorithms")
2+
3+
find_package(Ceres QUIET)
24
ocv_define_module(rgbd opencv_core opencv_calib3d opencv_imgproc OPTIONAL opencv_viz WRAP python)
5+
ocv_target_link_libraries(${the_module} ${CERES_LIBRARIES})
6+
7+
if(Ceres_FOUND)
8+
ocv_target_compile_definitions(${the_module} PUBLIC CERES_FOUND)
9+
else()
10+
message(STATUS "CERES support is disabled. Ceres Solver is Required for Posegraph optimization")
11+
endif()

modules/rgbd/include/opencv2/rgbd.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,7 @@
1313
#include "opencv2/rgbd/depth.hpp"
1414
#include "opencv2/rgbd/kinfu.hpp"
1515
#include "opencv2/rgbd/dynafu.hpp"
16+
#include "opencv2/rgbd/large_kinfu.hpp"
1617

1718

1819
/** @defgroup rgbd RGB-Depth Processing

modules/rgbd/include/opencv2/rgbd/dynafu.hpp

Lines changed: 4 additions & 96 deletions
Original file line numberDiff line numberDiff line change
@@ -10,103 +10,11 @@
1010
#include "opencv2/core.hpp"
1111
#include "opencv2/core/affine.hpp"
1212

13+
#include "kinfu.hpp"
14+
1315
namespace cv {
1416
namespace dynafu {
1517

16-
struct CV_EXPORTS_W Params
17-
{
18-
/** @brief Default parameters
19-
A set of parameters which provides better model quality, can be very slow.
20-
*/
21-
CV_WRAP static Ptr<Params> defaultParams();
22-
23-
/** @brief Coarse parameters
24-
A set of parameters which provides better speed, can fail to match frames
25-
in case of rapid sensor motion.
26-
*/
27-
CV_WRAP static Ptr<Params> coarseParams();
28-
29-
/** @brief frame size in pixels */
30-
CV_PROP_RW Size frameSize;
31-
32-
/** @brief camera intrinsics */
33-
CV_PROP Matx33f intr;
34-
35-
/** @brief pre-scale per 1 meter for input values
36-
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-
44-
/** @brief Depth sigma in meters for bilateral smooth */
45-
CV_PROP_RW float bilateral_sigma_depth;
46-
/** @brief Spatial sigma in pixels for bilateral smooth */
47-
CV_PROP_RW float bilateral_sigma_spatial;
48-
/** @brief Kernel size in pixels for bilateral smooth */
49-
CV_PROP_RW int bilateral_kernel_size;
50-
51-
/** @brief Number of pyramid levels for ICP */
52-
CV_PROP_RW int pyramidLevels;
53-
54-
/** @brief Resolution of voxel space
55-
56-
Number of voxels in each dimension.
57-
*/
58-
CV_PROP_RW Vec3i volumeDims;
59-
/** @brief Size of voxel in meters */
60-
CV_PROP_RW float voxelSize;
61-
62-
/** @brief Minimal camera movement in meters
63-
64-
Integrate new depth frame only if camera movement exceeds this value.
65-
*/
66-
CV_PROP_RW float tsdf_min_camera_movement;
67-
68-
/** @brief initial volume pose in meters */
69-
Affine3f volumePose;
70-
71-
/** @brief distance to truncate in meters
72-
73-
Distances to surface that exceed this value will be truncated to 1.0.
74-
*/
75-
CV_PROP_RW float tsdf_trunc_dist;
76-
77-
/** @brief max number of frames per voxel
78-
79-
Each voxel keeps running average of distances no longer than this value.
80-
*/
81-
CV_PROP_RW int tsdf_max_weight;
82-
83-
/** @brief A length of one raycast step
84-
85-
How much voxel sizes we skip each raycast step
86-
*/
87-
CV_PROP_RW float raycast_step_factor;
88-
89-
// gradient delta in voxel sizes
90-
// fixed at 1.0f
91-
// float gradient_delta_factor;
92-
93-
/** @brief light pose for rendering in meters */
94-
CV_PROP Vec3f lightPose;
95-
96-
/** @brief distance theshold for ICP in meters */
97-
CV_PROP_RW float icpDistThresh;
98-
/** angle threshold for ICP in radians */
99-
CV_PROP_RW float icpAngleThresh;
100-
/** number of ICP iterations for each pyramid level */
101-
CV_PROP std::vector<int> icpIterations;
102-
103-
/** @brief Threshold for depth truncation in meters
104-
105-
All depth values beyond this threshold will be set to zero
106-
*/
107-
CV_PROP_RW float truncateThreshold;
108-
};
109-
11018
/** @brief DynamicFusion implementation
11119
11220
This class implements a 3d reconstruction algorithm as described in @cite dynamicfusion.
@@ -132,11 +40,11 @@ struct CV_EXPORTS_W Params
13240
class CV_EXPORTS_W DynaFu
13341
{
13442
public:
135-
CV_WRAP static Ptr<DynaFu> create(const Ptr<Params>& _params);
43+
CV_WRAP static Ptr<DynaFu> create(const Ptr<kinfu::Params>& _params);
13644
virtual ~DynaFu();
13745

13846
/** @brief Get current parameters */
139-
virtual const Params& getParams() const = 0;
47+
virtual const kinfu::Params& getParams() const = 0;
14048

14149
/** @brief Renders a volume into an image
14250

modules/rgbd/include/opencv2/rgbd/kinfu.hpp

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -24,22 +24,22 @@ struct CV_EXPORTS_W Params
2424
/**
2525
* @brief Constructor for Params
2626
* Sets the initial pose of the TSDF volume.
27-
* @param volumeIntialPoseRot rotation matrix
28-
* @param volumeIntialPoseTransl translation vector
27+
* @param volumeInitialPoseRot rotation matrix
28+
* @param volumeInitialPoseTransl translation vector
2929
*/
30-
CV_WRAP Params(Matx33f volumeIntialPoseRot, Vec3f volumeIntialPoseTransl)
30+
CV_WRAP Params(Matx33f volumeInitialPoseRot, Vec3f volumeInitialPoseTransl)
3131
{
32-
setInitialVolumePose(volumeIntialPoseRot,volumeIntialPoseTransl);
32+
setInitialVolumePose(volumeInitialPoseRot,volumeInitialPoseTransl);
3333
}
3434

3535
/**
3636
* @brief Constructor for Params
3737
* Sets the initial pose of the TSDF volume.
38-
* @param volumeIntialPose 4 by 4 Homogeneous Transform matrix to set the intial pose of TSDF volume
38+
* @param volumeInitialPose 4 by 4 Homogeneous Transform matrix to set the intial pose of TSDF volume
3939
*/
40-
CV_WRAP Params(Matx44f volumeIntialPose)
40+
CV_WRAP Params(Matx44f volumeInitialPose)
4141
{
42-
setInitialVolumePose(volumeIntialPose);
42+
setInitialVolumePose(volumeInitialPose);
4343
}
4444

4545
/**
@@ -77,7 +77,7 @@ struct CV_EXPORTS_W Params
7777
/** @brief frame size in pixels */
7878
CV_PROP_RW Size frameSize;
7979

80-
CV_PROP_RW cv::kinfu::VolumeType volumeType;
80+
CV_PROP_RW kinfu::VolumeType volumeType;
8181

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

0 commit comments

Comments
 (0)