orb_slam3_details/Examples/RGB-D-Inertial/RealSense_D435i.yaml

91 lines
2.6 KiB
YAML
Executable File

%YAML:1.0
#--------------------------------------------------------------------------------------------
# Camera Parameters. Adjust them!
#--------------------------------------------------------------------------------------------
File.version: "1.0"
Camera.type: "PinHole"
# Right Camera calibration and distortion parameters (OpenCV)
Camera1.fx: 617.201
Camera1.fy: 617.362
Camera1.cx: 324.637
Camera1.cy: 242.462
# distortion parameters
Camera1.k1: 0.0
Camera1.k2: 0.0
Camera1.p1: 0.0
Camera1.p2: 0.0
# Camera resolution
Camera.width: 640
Camera.height: 480
# Camera frames per second
Camera.fps: 30
# Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
Camera.RGB: 1
Stereo.ThDepth: 40.0
Stereo.b: 0.0745
# Depth map values factor
RGBD.DepthMapFactor: 1000.0
# Transformation from body-frame (imu) to left camera
IMU.T_b_c1: !!opencv-matrix
rows: 4
cols: 4
dt: f
data: [0.999903, -0.0138036, -0.00208099, -0.0202141,
0.0137985, 0.999902, -0.00243498, 0.00505961,
0.0021144, 0.00240603, 0.999995, 0.0114047,
0.0, 0.0, 0.0, 1.0]
# Do not insert KFs when recently lost
IMU.InsertKFsWhenLost: 0
# IMU noise (Use those from VINS-mono)
IMU.NoiseGyro: 1e-2 # 3 # 2.44e-4 #1e-3 # rad/s^0.5
IMU.NoiseAcc: 1e-1 #2 # 1.47e-3 #1e-2 # m/s^1.5
IMU.GyroWalk: 1e-6 # rad/s^1.5
IMU.AccWalk: 1e-4 # m/s^2.5
IMU.Frequency: 200.0
#--------------------------------------------------------------------------------------------
# ORB Parameters
#--------------------------------------------------------------------------------------------
# ORB Extractor: Number of features per image
ORBextractor.nFeatures: 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
#--------------------------------------------------------------------------------------------
# Viewer Parameters
#--------------------------------------------------------------------------------------------
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1.0
Viewer.GraphLineWidth: 0.9
Viewer.PointSize: 2.0
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3.0
Viewer.ViewpointX: 0.0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -3.5
Viewer.ViewpointF: 500.0