Closed JinLn closed 4 years ago
One way to solve the problem is to modify file KITTIXXX.yaml , add camera model and camera parameters in opencv format by referring to file EuRoC.yaml.
In the latest version commit id 5e9189, without specified camera model in settings file will let ORB_SLAM3::Tracking::mpCamera
uninitialized (nullptr). This null pointer will be passed to ORB_SLAM3::KeyFrame
and ORB_SLAM3::EdgeSE3ProjectXYZOnlyPose
, finally make illegal memory access during optimizing frame pose. This is why segment fault occured. BTW, similar errors also occured when testing ORB_SLAM3 in RGB-D mode on the TUM RGB-D sequence (but to solve it we have to modify some code except setting file(s).).
Here is a example of modified KITTI00-02.yaml :
%YAML:1.0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
# ===> NOTICE: Add camera model here <===
Camera.type: "PinHole"
# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 718.856
Camera.fy: 718.856
Camera.cx: 607.1928
Camera.cy: 185.2157
Camera.k1: 0.0
Camera.k2: 0.0
Camera.p1: 0.0
Camera.p2: 0.0
Camera.bFishEye: 0
Camera.width: 1241
Camera.height: 376
# Camera frames per second
Camera.fps: 10.0
# stereo baseline times fx
Camera.bf: 386.1448
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1
# Close/Far threshold. Baseline times.
ThDepth: 35
# ============================================================
# ===> NOTICE: Add camera parameters here <===
LEFT.height: 1241
LEFT.width: 376
LEFT.D: !!opencv-matrix
rows: 1
cols: 5
dt: d
data: [0.0, 0.0, 0.0, 0.0, 0.0]
LEFT.K: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [718.856, 0.0, 607.1928, 0.0, 718.856, 185.2157, 0.0, 0.0, 1.0]
LEFT.R: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
LEFT.P: !!opencv-matrix
rows: 3
cols: 4
dt: d
data: [7.188560000000e+02, 0.000000000000e+00, 6.071928000000e+02, 0.000000000000e+00, 0.000000000000e+00, 7.188560000000e+02, 1.852157000000e+02, 0.000000000000e+00, 0.000000000000e+00, 0.000000000000e+00, 1.000000000000e+00, 0.000000000000e+00]
RIGHT.height: 1241
RIGHT.width: 376
RIGHT.D: !!opencv-matrix
rows: 1
cols: 5
dt: d
data: [0.0, 0.0, 0.0, 0.0, 0.0]
RIGHT.K: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [718.856, 0.0, 607.1928, 0.0, 718.856, 185.2157, 0.0, 0.0, 1.0]
RIGHT.R: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [0.9999633526194376, -0.003625811871560086, 0.007755443660172947, 0.003680398547259526, 0.9999684752771629, -0.007035845251224894, -0.007729688520722713, 0.007064130529506649, 0.999945173484644]
RIGHT.P: !!opencv-matrix
rows: 3
cols: 4
dt: d
data: [7.188560000000e+02, 0.000000000000e+00, 6.071928000000e+02, -3.861448000000e+02, 0.000000000000e+00, 7.188560000000e+02, 1.852157000000e+02, 0.000000000000e+00, 0.000000000000e+00, 0.000000000000e+00, 1.000000000000e+00, 0.000000000000e+00]
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 2000
# ORB Extractor: Scale factor between levels in the scale pyramid
ORBextractor.scaleFactor: 1.2
# ORB Extractor: Number of levels in the scale pyramid
ORBextractor.nLevels: 8
# ORB Extractor: Fast threshold
# Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
# Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
# You can lower these values if your images have low contrast
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7
#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.6
Viewer.KeyFrameLineWidth: 2
Viewer.GraphLineWidth: 1
Viewer.PointSize: 2
Viewer.CameraSize: 0.7
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -100
Viewer.ViewpointZ: -0.1
Viewer.ViewpointF: 2000
I can test ORB-SLAM3 successfully in stereo-only mode on KITTI odometry sequence 00. Hope to help you.
Thank you very much . I tested KITTI odometry sequence 03 like you and successed . Thank you again
how do you know these parameters@DreamWaterFound
how do you know these parameters@DreamWaterFound
LEFT.D
、LEFT.K
、RIGHT.D
、RIGHT.K
were provided by KITTIXXX.yaml
.
LEFT.R
、LEFT.P
、RIGHT.R
、RIGHT.P
were derived from P0
P1
in the calib.txt
. You can download this file from this page.
谢谢!邮件已收到。
谢谢!邮件已收到。
how do you know these parameters@DreamWaterFound
LEFT.D
、LEFT.K
、RIGHT.D
、RIGHT.K
were provided byKITTIXXX.yaml
.LEFT.R
、LEFT.P
、RIGHT.R
、RIGHT.P
were derived fromP0
P1
in thecalib.txt
. You can download this file from this page.
hi, what is this parameter : ThDepth and how do i get it;
hi, what is this parameter : ThDepth and how do i get it;
See the section III.A in the paper of ORB-SLAM2. Empirically set it to 40.
E:\orb slam 3 test\orbslam test 4\x64\Release>"E:\orb slam 3 test\orbslam test 4\x64\Release\orbslam test 1.exe" "E:/vcpkg/ORB_SLAM3/Vocabulary/ORBvoc.txt" "E:/vcpkg/ORB_SLAM3/Examples/Stereo/KITTI0000.yaml" "D:/dataset/sequences/00" Loaded 4541 timestamps. Number of images to process: 4541
ORB-SLAM3 Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. ORB-SLAM2 Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. This program comes with ABSOLUTELY NO WARRANTY; This is free software, and you are welcome to redistribute it under certain conditions. See LICENSE.txt.
Input sensor was set to: Stereo
Loading ORB Vocabulary. This could take a while... Vocabulary loaded!
Initialization of Atlas from scratch Creation of new map with id: 0 Creation of new map with last KF id: 0 Seq. Name:
Camera Parameters:
Depth Threshold (Close/Far Points): 21.4866
ORB Extractor Parameters:
Start processing sequence ... Images in the sequence: 4541
Loading images at index 0 Successfully loaded images at index 0 Processing frame 0 with timestamp 0
E:\orb slam 3 test\orbslam test 4\x64\Release>
any help please ? i used the above yaml i am using windows
谢谢!邮件已收到。
When i executted Kitti dataset, it meet a trouble like this:
Segmentation fault (core dumped)
Have someone meet this toruble like me and how to deal with ? tkanks! All the thing like this: `./stereo_kitti /home/jinln/jinln/ORB_SLAM3/Vocabulary/ORBvoc.txt /home/jinln/jinln/ORB_SLAM3/Examples/Stereo/KITTI03.yaml /home/jinln/jinln/DATASET/kitti/03 ORB-SLAM3 Copyright (C) 2017-2020 Carlos Campos, Richard Elvira, Juan J. Gómez, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. ORB-SLAM2 Copyright (C) 2014-2016 Raúl Mur-Artal, José M.M. Montiel and Juan D. Tardós, University of Zaragoza. This program comes with ABSOLUTELY NO WARRANTY; This is free software, and you are welcome to redistribute it under certain conditions. See LICENSE.txt.Input sensor was set to: Stereo
Loading ORB Vocabulary. This could take a while... Vocabulary loaded!
Creation of new map with id: 0 Creation of new map with last KF id: 0 Seq. Name:
Camera Parameters:
ORB Extractor Parameters:
Depth Threshold (Close/Far Points): 21.486
Start processing sequence ... Images in the sequence: 801
First KF:0; Map init KF:0 New Map created with 1315 points Segmentation fault (core dumped) `