orb_slam3_details/Examples_old/Monocular-Inertial/TUM-VI.yaml

92 lines
3.3 KiB
YAML
Raw Normal View History

2022-03-28 21:20:28 +08:00
%YAML:1.0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
Camera.type: "KannalaBrandt8"
# Camera calibration and distortion parameters (OpenCV)
Camera.fx: 190.978477 # 190.97847715128717
Camera.fy: 190.973307 # 190.9733070521226
Camera.cx: 254.931706 # 254.93170605935475
Camera.cy: 256.897442 # 256.8974428996504
# Equidistant distortion 0.0034823894022493434, 0.0007150348452162257, -0.0020532361418706202, 0.00020293673591811182
#Camera.bFishEye: 1
Camera.k1: 0.003482389402 # 0.0034823894022493434
Camera.k2: 0.000715034845 # 0.0007150348452162257
Camera.k3: -0.002053236141 # -0.0020532361418706202
Camera.k4: 0.000202936736 # 0.00020293673591811182
# Camera resolution
Camera.width: 512
Camera.height: 512
# Camera frames per second
Camera.fps: 20.0
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1
# Transformation from body-frame (imu) to camera
Tbc: !!opencv-matrix
rows: 4
cols: 4
dt: f
data: [-0.9995250378696743, 0.0075019185074052044, -0.02989013031643309, 0.045574835649698026,
0.029615343885863205, -0.03439736061393144, -0.998969345370175, -0.071161801837997044,
-0.008522328211654736, -0.9993800792498829, 0.03415885127385616, -0.044681254117144367,
0.0, 0.0, 0.0, 1.0]
# Tbc: !!opencv-matrix # from vins mono calibration file
# rows: 4
# cols: 4
# dt: f
# data: [-0.9995250378696743, 0.0075842033363785165, -0.030214670573904204, 0.044511917113940799,
# 0.029940114644659861, -0.034023430206013172, -0.99897246995704592, -0.073197096234105752,
# -0.0086044170750674241, -0.99939225835343004, 0.033779845322755464, -0.047972907300764499,
# 0.0, 0.0, 0.0, 1.0]
# IMU noise (Use those from VINS-mono)
IMU.NoiseGyro: 0.00016 # rad/s^0.5
IMU.NoiseAcc: 0.0028 # m/s^1.5
IMU.GyroWalk: 0.000022 # rad/s^1.5
IMU.AccWalk: 0.00086 # m/s^2.5
IMU.Frequency: 200
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 1500 # Tested with 1250
# 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
ORBextractor.iniThFAST: 20 # 20
ORBextractor.minThFAST: 7 # 7
#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1
Viewer.GraphLineWidth: 0.9
Viewer.PointSize: 2
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3
Viewer.ViewpointX: 0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -3.5 # -1.8
Viewer.ViewpointF: 500