This tutorial provides the explanation of the workflow of Misc3D RGBD dense reconstruction. We use the code in example
and dataset in data
for demonstration.
- Install OpenCV C++ library in your system.
- Configure the
cmake
to find the path to OpenCV. - Set
BUILD_RECONSTRUCTION
ON.
As shown in data
folder, you should create two folders, color
and depth
, storing the color and depth images seperately (you can change the name of data
to other name). The naming of the images is not required to be the same as demonstrated in this tutorial but need to stored with identity order. Please save your color image in png
format.
Create a json
file with the following elements:
"data_path": "../data",
"camera": {
"width": 640,
"height": 480,
"fx": 598.7568,
"fy": 598.7568,
"cx": 326.3443,
"cy": 250.2448,
"depth_scale": 1000.0
},
"make_fragments": {
"descriptor_type": "orb",
"feature_num": 100,
"n_frame_per_fragment": 40,
"keyframe_ratio": 0.5
},
"local_refine": "color",
"global_registration": "teaser",
"optimization_param": {
"preference_loop_closure_odometry": 0.1,
"preference_loop_closure_registration": 5.0
},
"depth_max": 3.0,
"depth_diff_max": 0.05,
"voxel_size": 0.01,
"integration_voxel_size": 0.008,
"tsdf_integration": false
"enable_slac": false
These are the whole parameters of the reconstruction pipeline that can be tuned. If you do not specify part of these parameters, the default value will be used.
-
camera
: Specify the width, height, fx, fy, cx, cy, depth_scale of the RGBD camera. -
make_fragments
:descriptor_type
: The type of feature descriptor. It can beorb
orsift
.feature_num
: The number of features extracted from each color image.n_frame_per_fragment
: The number of frames used to make a fragment.keyframe_ratio
: The ratio of keyframes used for loop closure computation.
-
local_refine
: Fragements are refined by ICP, which has the variant ofpoint2point
,point2plane
,color
andgeneralized
. -
global_registration
: The type of global registration method. It can beteaser
orransac
. -
optimization_param
:preference_loop_closure_odometry
: The preference of loop closure odometry.preference_loop_closure_registration
: The preference of loop closure registration.
-
depth_max
: The maximum depth value to limit the depth range. -
depth_diff_max
: The maximum depth difference between two consecutive frames. -
voxel_size
: The voxel size used to downsampling the fragments point cloud. -
integration_voxel_size
: The voxel size used to create TSDF volume. -
tsdf_integration
: Enable TSDF integration will create triangle mesh for the scene, otherwise only point clouds will be integrated. -
enable_slac
: Whether to enable SLAC for fragments pose graph optimization.
Run the pipeline by serveral lines of code:
config_path = 'config.json'
pipeline = m3d.reconstruction.ReconstructionPipeline(config_path)
pipeline.run_system()
data/fragments
: The integrated fragments point cloud and its pose graph file.data/scene
: The reconstructed scene triangle mesh and the trajectory json file which stores the whole odometry of the RGBD data.