introlab / rtabmap

RTAB-Map library and standalone application
https://introlab.github.io/rtabmap
Other
2.72k stars 775 forks source link

I find some problem when use RTAB-MAP to get VO and Loop constrains as I put KITTI_00 dataset as the input #265

Open forthealllight opened 6 years ago

forthealllight commented 6 years ago

Hi , it‘s kind of you to share the excellent code 。And give me the parameters in ".ini" files。 When I use the KITTI dataset as input to run RTAB,in order to get the VO and Loop closure constains。 Sincere, I want to get the all poses and all loop closures。In the following is my configuration。

[Camera] calibrationName=KITTI_07 type=1 stereo\driver=2 StereoImages\path_left=~/Downloads/KITTI/dataset/sequences/07/image_0 StereoImages\path_right=~/Downloads/KITTI/dataset/sequences/07/image_1 stereo\depthGenerated=false Images\stamps=~/Downloads/KITTI/dataset/sequences/07/times.txt Images\path_scans=~/Downloads/KITTI/dataset/sequences/07/velodyne Images\scan_transform=-0.27 0 0.08 0 0 0 Images\scan_max_pts=130000 Images\gt_path=~/Downloads/KITTI/devkit/cpp/data/odometry/poses/07.txt Images\gt_format=2 Images\scan_downsample_step=10 Images\scan_voxel_size=0.3

[Core] Rtabmap\CreateIntermediateNodes=true Rtabmap\ImageBufferSize=0

Odom\Strategy=1 Odom\ImageBufferSize=0

GFTT\MinDistance=10 GFTT\QualityLevel=0.002

Icp\CorrespondenceRatio=0.1 Icp\Iterations=10 Icp\MaxCorrespondenceDistance=0.3 Icp\MaxTranslation=0 Icp\PointToPlane=true Icp\VoxelSize=0 Icp\Epsilon=0.01

Reg\Strategy=0

Vis\EstimationType=1 Vis\PnPFlags=0 Vis\PnPReprojError=1 Vis\CorFlowWinSize=15 Vis\CorType=1

Futhermore, this configuration is not work well ,the loop closures detection only happen in the first 107 frames ,so I set: "Reg\Strategy=2"

So it seem work better ,but I can not get the all poses , meanwhile , the loop closures detection skip some frames , when I output the poses in a ".g2o" file , it is only 12 poses。

I think maybe I should change the " source input rate" and the “detect rate ” ,so I change " source input rate=1HZ" “detect rate =0HZ”

after that it seem can ouput all poses ,but when I run the code , it’s wrong with the warning:

"computeTransformationImpl() Optical flow correspondences requires images in data!"。

I do not know whiy ?

In a word , what I should do to get the all poses and the all loop closures?

Best wishes Thank you so much

matlabbe commented 6 years ago

These are parameters used with an older version of rtabmap, like in this video (created if I remember in 2015): https://www.youtube.com/watch?v=xIGKaE_rZ_Q

To make optical flow work with current master version (for loop closure detection), you should set Mem/ImageKept=true to fix "computeTransformationImpl() Optical flow correspondences requires images in data!" error. This bug has been fixed in devel.

To use pure VO with optical flow, keep Reg/Strategy=0 and remove velodyne path.

Indeed, the GUI is an online tool, which is unconvenient to benchmark datasets with which we want to process all frames even if the processing cannot be not real-time (because of different computer performance). The source rate should be lower than rate at which odometry/rtabmap can process the frames to get all poses (like you did). In devel branch, there is a new tool called rtabmap-kitti_dataset for convenience that can process offline any sequence of the kitti dataset. I am still working on it, so there is no documentation yet about it, only default usage (see example shown). For best results, rtabmap should have been built with g2o support.

cheers, Mathieu