Comments (8)
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.
from orb_slam3.
Thank you very much . I tested KITTI odometry sequence 03 like you and successed . Thank you again
from orb_slam3.
how do you know these parameters@DreamWaterFound
from orb_slam3.
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.
from orb_slam3.
from orb_slam3.
from orb_slam3.
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;
from orb_slam3.
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.
from orb_slam3.
Related Issues (20)
- SOS!!!I want to run the ROS example, but I get this error and the compilation of the build_ros.sh is error-free. HOT 1
- Stereo fisheye odometry
- i had a problem when loading atlas maps:terminate called after throwing an instance of 'boost::archive::archive_exception' what(): input stream error Aborted (core dumped)
- How to set initial pose in ORB-SLAM3 Mono HOT 4
- Getting the last n keyframes in real time
- points and path disappear and start over, every minute in ORB SLAM3 Ros HOT 2
- LoopClosing not working?
- error in Tracking::PreintegrateIMU() function HOT 1
- question about the variable avgA in class IMU::Preintegrated
- Distance issue displayed during orbslam3 positioning
- Merging maps when recently lost or recolalization has been recently
- Dose Stereo-image can reconstruct dense point cloud?
- trajectory
- Empty IMU measurements vector!!! HOT 2
- Empty IMU measurements vector!!!
- Issue trying to compile and install ORB_SLAM3 HOT 1
- .
- Segmentation Fault issue during runtime - Eigen::internal::cast_impl
- Segmentation fault on SaveTrajectoryTUM in rgbd_inertial_realsense_D435i
- Segmentation fault on RGB node with D435i camera
Recommend Projects
-
React
A declarative, efficient, and flexible JavaScript library for building user interfaces.
-
Vue.js
🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.
-
Typescript
TypeScript is a superset of JavaScript that compiles to clean JavaScript output.
-
TensorFlow
An Open Source Machine Learning Framework for Everyone
-
Django
The Web framework for perfectionists with deadlines.
-
Laravel
A PHP framework for web artisans
-
D3
Bring data to life with SVG, Canvas and HTML. 📊📈🎉
-
Recommend Topics
-
javascript
JavaScript (JS) is a lightweight interpreted programming language with first-class functions.
-
web
Some thing interesting about web. New door for the world.
-
server
A server is a program made to process requests and deliver data to clients.
-
Machine learning
Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.
-
Visualization
Some thing interesting about visualization, use data art
-
Game
Some thing interesting about game, make everyone happy.
Recommend Org
-
Facebook
We are working to build community through open source technology. NB: members must have two-factor auth.
-
Microsoft
Open source projects and samples from Microsoft.
-
Google
Google ❤️ Open Source for everyone.
-
Alibaba
Alibaba Open Source for everyone
-
D3
Data-Driven Documents codes.
-
Tencent
China tencent open source team.
from orb_slam3.