Skip to content

Benchmark SLAM

matlabbe edited this page Jan 17, 2018 · 70 revisions

Under construction...

RGB-D Datasets

RGBD-SLAM Dataset

Link: http://vision.in.tum.de/data/datasets/rgbd-dataset

Camera calibration

Image width		640 pixels
Image height	480 pixels
Focal length	525
Image center x	319.5 pixels
Image center y	239.5 pixels
Depth scale		5

Parameters

[Camera]
calibrationName=rgbdslam
type=0
rgbd\driver=6
RGBDImages\path_rgb=~/Downloads/rgbd_dataset_freiburg3_long_office_household/rgb_sync
RGBDImages\path_depth=~/Downloads/rgbd_dataset_freiburg3_long_office_household/depth_sync
RGBDImages\scale=5
Images\filenames_as_stamps=true
Images\gt_path=~/Downloads/rgbd_dataset_freiburg3_long_office_household/groundtruth.txt
Images\gt_format=1

ScanFromDepth\enabled=true
ScanFromDepth\decimation=16
ScanFromDepth\maxDepth=4
ScanFromDepth\voxelSize=0.05
ScanFromDepth\normalsK=6

[Core]
Reg\Strategy=2
Odom\Strategy=1

Icp\CorrespondenceRatio=0.1
Icp\DownsamplingStep=1
Icp\Epsilon=0
Icp\Iterations=30
Icp\MaxCorrespondenceDistance=0.03
Icp\MaxRotation=0.78
Icp\MaxTranslation=0.2
Icp\PointToPlane=true
Icp\PointToPlaneNormalNeighbors=20
Icp\VoxelSize=0

RGB-D Dataset 7-Scenes

Link: http://research.microsoft.com/en-us/projects/7-scenes/

Note: The depth images are not registered with the RGB images. Use ICP registration approach.

Camera calibration

Image width		640 pixels
Image height	480 pixels
Focal length	585
Image center x	319.5 pixels
Image center y	239.5 pixels
Depth scale		1

Parameters

[Camera]
calibrationName=7scenes
type=0
rgbd\driver=6
RGBDImages\path_rgb=~/Downloads/fire/seq-01/rgb
RGBDImages\path_depth=~/Downloads/fire/seq-01/depth
RGBDImages\scale=5
Images\filenames_as_stamps=false
Images\gt_path=~/Downloads/fire/seq-01/poses
Images\gt_format=9

Tracking a Depth Camera: Parameter Exploration for Fast ICP

Link: http://projects.asl.ethz.ch/datasets/doku.php?id=kinect:iros2011kinect

Note: Only point clouds, so visual loop closure cannot be used.

Stereo Datasets

KITTI Dataset

Link: http://www.cvlibs.net/datasets/kitti/

Camera calibration

Extract KITTI_calibrations.zip in ~/Documents/RTAB-Map/camera_info.

Parameters

[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

Note that PnP refine with OpenCV 3 is not super stable, set Vis/PnPRefineIterations to 0. Note that Reg\Strategy can be set to 1 or 2 if the Velodyne path is set.

The New College Vision and Laser Data Set

Link: http://www.robots.ox.ac.uk/NewCollegeData/index.php

$ rectify.exe Images/ Bumblebee-8090375-BiLUT-512x384.lut
$ uALogParser.exe NewCollege_3_11_2008__FinalLog.alog GPS --fields time,X,Y -o GPS

Camera parameters

20 Hz
Image width	512 pixels
Image height	384 pixels
Focal length	389.956085 pixels
Image center x	254.903519 pixels
Image center y	201.899490 pixels
Camera baseline	0.120005 m
Camera internal time delay 0.05 s
Camera transform with optical rotation (xyz roll,pitch,yaw) [-0.062 0.205 0.837 -1.7977 0 -1.5708]

The Málaga Stereo and Laser Urban Data Set

Link: http://www.mrpt.org/MalagaUrbanDataset

Split images in two directories:
$ cd malaga-urban-dataset-extract-01_rectified_800x600_Images/
$ mkdir left right
$ mv *_left.jpg left/.
$ mv *_right.jpg right/.

Camera calibration

cx=404.00760
cy=309.05989
fx=621.18428
fy=621.18428
baseline=0.119471

Pose (xyz, ypr) = [0.785 0 0.273 0 −8.2deg 0]
Pose with optical rotation: 
[0 0.1426 0.9898 0.785 -1 0 0 0 0 -0.9898 0.1426 0.273]

Parameters

[Camera]
calibrationName=malaga_urban
type=1
localTransform=0 0.1426 0.9898 0.785 -1 0 0 0 0 -0.9898 0.1426 0.273
stereo\driver=2
StereoImages\path_left=~/Downloads/malaga-urban-dataset-extract-01/malaga-urban-dataset-extract-01_rectified_800x600_Images/left
StereoImages\path_right=~/Downloads/malaga-urban-dataset-extract-01/malaga-urban-dataset-extract-01_rectified_800x600_Images/right
Images\filenames_as_stamps=true
Images\gt_path=~/Downloads/malaga-urban-dataset-extract-01/malaga-urban-dataset-extract-01_all-sensors_GPS.txt
Images\gt_format=6

UQ St Lucia Stereo Vehicular Dataset

http://asrl.utias.utoronto.ca/~mdw/uqstluciadataset.html

Extract timestamps from 101215_153851_MultiCamera0.log file. For example, if we process images cam0_image01500.png to cam0_image01600.png, copy time stamps (###.####) from 1500 to 1600 (same number of lines) to a file stlucia_stamps.txt.

Use 101215_153851_Ins0.log as ground truth file.

Camera (1024x768)
Focal Length X,Y (pixels)
Principle Point (x,y) (pixels)
Distortions (K1,K2,P1,P2,K3)
Left
1246.56167, 1247.09234
532.28794, 383.60407
[-0.32598 0.18151 0.00033 -0.00045 0.00000]
Right
1244.80505, 1245.81569
506.63554, 390.70481
[-0.32512 0.17124 0.00003 0.00003 0.00000]

Stereo Extrinsics:
Translation, t (x, y, z, in mm) : -750.66669, -3.85768, 3.09594
Euler rotations (format RxRyRz) (radians) : -0.00515, -0.00531, -0.00134
In meters: [-0.75066669 -0.00385768, 0.00309594 -0.00515 -0.00531 -0.00134]

UQ Indoor Level 7 S-Block Dataset

https://wiki.qut.edu.au/display/cyphy/Indoor+Level+7+S-Block+Dataset

Karlsruhe Dataset

Link: http://www.cvlibs.net/datasets/karlsruhe_sequences/

Create calibration files with only P#_roi (of file 2009_09_08_calib.txt).

karlsruhe_left.yaml:

%YAML:1.0
projection_matrix:
  rows: 3
  cols: 4
  data: [ 6.790081e+02, 0.000000e+00, 6.598034e+02, 0.000000e+00, 0.000000e+00, 6.790081e+02, 1.865724e+02, 0.000000e+00, 0.000000e+00, 0.000000e+00, 1.000000e+00, 0.000000e+00 ]

karlsruhe_right.yaml:

%YAML:1.0
projection_matrix:
  rows: 3
  cols: 4
  data: [ 6.790081e+02, 0.000000e+00, 6.598034e+02, -3.887481e+02, 0.000000e+00, 6.790081e+02, 1.865724e+02, 0.000000e+00, 0.000000e+00, 0.000000e+00, 1.000000e+00, 0.000000e+00 ]

Ground truth: use Karlsruhe format. The ground truth file (insdata.txt) must have the same number of lines than the images.

Devon Island Rover Navigation Dataset

Link: http://asrl.utias.utoronto.ca/datasets/devon-island-rover-navigation/

Camera calibration, Rectified, 1280x960
Baseline:	0.239977002
Focal Length:	968.999694824
ImageCenter (row, col):	463.537109375 635.139038086
Resolution (rows, cols):	960 1280

Camera calibration, Rectified, 512x384 
Baseline:	0.239977
Focal Length:	387.599884
ImageCenter (row, col):	185.114852905 253.755615234
Resolution (rows, cols):	384 512

Parameters

Vis\MaxDepth=20
stereo\depthGenerated=true

Gravel Pit Lidar-Intensity Imagery Dataset

Link: http://asrl.utias.utoronto.ca/datasets/abl-sudbury/

ICL-NUIM Dataset

Link: http://www.doc.ic.ac.uk/%7Eahanda/VaFRIC/iclnuim.html

Malaga dataset 2009 with 6D ground truth

Link: http://www.mrpt.org/malaga_dataset_2009

Important: The left and right rectified images don't have their optical center aligned on y-axis, which is required by RTAB-Map. The cameras also don't face exactly the same direction and they are not fixed on the same baseline (pose in y and z should be identical with no rotation between the cameras). To be used in RTAB-Map, the images should be rectified again with the previous requirements. Another problem is that images are not synchronized (left and right images are not taken exactly at the same time).

Camera calibration

From malaga_datasets_grabber.ini:

// Pose of the left camera on the robot:
pose_x			= 2.2157; position on the robot (meters)
pose_y			= 0.4303 // pose_y right = -0.4268 -> baseline = 0.4303 - (-0.4268) = -0.8571 m
pose_z			= 0.0219
pose_yaw		= -88.43	; Angles in degrees
pose_pitch		= -2.99
pose_roll		= -87.23
// xyz rpy: [2.2157 0.4303 0.0219 -1.5224 -0.05218 -1.54339] 

// Calibration parameters (left camera)
dc1394_frame_width	= 1024
dc1394_frame_height	= 768
calib_params    = 923.5295 922.2418 507.2222 383.5822           // fx fy cx cy
distort_params  = -0.353754 0.162014 1.643379e-03 3.655471e-04  // k1 k2 p1 p2

// Calibration parameters (right camera)
dc1394_frame_width	= 1024
dc1394_frame_height	= 768
calib_params    = 911.3657 909.3910 519.3951 409.0285  -781.1315 // fx fy cx cy Tx
distort_params  = -0.339539 0.140431 2.969822e-04 -1.405876e-04  // k1 k2 p1 p2

Use GT_path_vehicle_interp.txt as ground truth.

Clone this wiki locally