RealSense_D435i.yaml 2.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990
  1. %YAML:1.0
  2. #--------------------------------------------------------------------------------------------
  3. # Camera Parameters. Adjust them!
  4. #--------------------------------------------------------------------------------------------
  5. File.version: "1.0"
  6. Camera.type: "PinHole"
  7. # Right Camera calibration and distortion parameters (OpenCV)
  8. Camera1.fx: 617.201
  9. Camera1.fy: 617.362
  10. Camera1.cx: 324.637
  11. Camera1.cy: 242.462
  12. # distortion parameters
  13. Camera1.k1: 0.0
  14. Camera1.k2: 0.0
  15. Camera1.p1: 0.0
  16. Camera1.p2: 0.0
  17. # Camera resolution
  18. Camera.width: 640
  19. Camera.height: 480
  20. # Camera frames per second
  21. Camera.fps: 30
  22. # Color order of the images (0: BGR, 1: RGB. It is ignored if images are grayscale)
  23. Camera.RGB: 1
  24. Stereo.ThDepth: 40.0
  25. Stereo.b: 0.0745
  26. # Depth map values factor
  27. RGBD.DepthMapFactor: 1000.0
  28. # Transformation from body-frame (imu) to left camera
  29. IMU.T_b_c1: !!opencv-matrix
  30. rows: 4
  31. cols: 4
  32. dt: f
  33. data: [0.999903, -0.0138036, -0.00208099, -0.0202141,
  34. 0.0137985, 0.999902, -0.00243498, 0.00505961,
  35. 0.0021144, 0.00240603, 0.999995, 0.0114047,
  36. 0.0, 0.0, 0.0, 1.0]
  37. # Do not insert KFs when recently lost
  38. IMU.InsertKFsWhenLost: 0
  39. # IMU noise (Use those from VINS-mono)
  40. IMU.NoiseGyro: 1e-2 # 3 # 2.44e-4 #1e-3 # rad/s^0.5
  41. IMU.NoiseAcc: 1e-1 #2 # 1.47e-3 #1e-2 # m/s^1.5
  42. IMU.GyroWalk: 1e-6 # rad/s^1.5
  43. IMU.AccWalk: 1e-4 # m/s^2.5
  44. IMU.Frequency: 200.0
  45. #--------------------------------------------------------------------------------------------
  46. # ORB Parameters
  47. #--------------------------------------------------------------------------------------------
  48. # ORB Extractor: Number of features per image
  49. ORBextractor.nFeatures: 1250
  50. # ORB Extractor: Scale factor between levels in the scale pyramid
  51. ORBextractor.scaleFactor: 1.2
  52. # ORB Extractor: Number of levels in the scale pyramid
  53. ORBextractor.nLevels: 8
  54. # ORB Extractor: Fast threshold
  55. # Image is divided in a grid. At each cell FAST are extracted imposing a minimum response.
  56. # Firstly we impose iniThFAST. If no corners are detected we impose a lower value minThFAST
  57. # You can lower these values if your images have low contrast
  58. ORBextractor.iniThFAST: 20
  59. ORBextractor.minThFAST: 7
  60. #--------------------------------------------------------------------------------------------
  61. # Viewer Parameters
  62. #--------------------------------------------------------------------------------------------
  63. Viewer.KeyFrameSize: 0.05
  64. Viewer.KeyFrameLineWidth: 1.0
  65. Viewer.GraphLineWidth: 0.9
  66. Viewer.PointSize: 2.0
  67. Viewer.CameraSize: 0.08
  68. Viewer.CameraLineWidth: 3.0
  69. Viewer.ViewpointX: 0.0
  70. Viewer.ViewpointY: -0.7
  71. Viewer.ViewpointZ: -3.5
  72. Viewer.ViewpointF: 500.0