velodyne16_lio_sam_dataset.yaml 4.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102
  1. common:
  2. lid_topic: /points_raw #"/velodyne_points"
  3. imu_topic: /imu_raw #"/imu/data"
  4. gnss_topic: /gps/fix #"/imu/data"
  5. time_sync_en: false # ONLY turn on when external time synchronization is really not possible
  6. #NCLT
  7. # lid_topic: "/points_raw"
  8. # imu_topic: "/imu_raw"
  9. #KITTI
  10. # lid_topic: "/kitti/velo/pointcloud"
  11. # imu_topic: "/kitti/oxts/imu"
  12. #RS LiDar
  13. # lid_topic: "/rslidar"
  14. # imu_topic: "/imu"
  15. preprocess:
  16. lidar_type: 2 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR,
  17. scan_line: 16
  18. scan_rate: 10 # only need to be set for velodyne, unit: Hz,
  19. blind: 1
  20. mapping:
  21. acc_cov: 3.9939570888238808e-03
  22. gyr_cov: 1.5636343949698187e-03
  23. b_acc_cov: 6.4356659353532566e-05
  24. b_gyr_cov: 3.5640318696367613e-05
  25. fov_degree: 180
  26. det_range: 100.0
  27. extrinsic_est_en: true # true: enable the online estimation of IMU-LiDAR extrinsic,
  28. extrinsic_T: [ 0, 0, 0]
  29. extrinsic_R: [ -1, 0, 0,
  30. 0, 1, 0,
  31. 0, 0, -1]
  32. extrinT_Gnss2Lidar: [ 0, 0, 0]
  33. extrinR_Gnss2Lidar: [ 1, 0, 0,
  34. 0, 1, 0,
  35. 0, 0, 1]
  36. publish:
  37. path_en: true
  38. scan_publish_en: true # false: close all the point cloud output
  39. dense_publish_en: true # false: low down the points number in a global-frame point clouds scan.
  40. scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame
  41. pcd_save:
  42. pcd_save_en: true
  43. interval: -1 # how many LiDAR frames saved in each pcd file;
  44. # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames.
  45. # voxel filter paprams
  46. odometrySurfLeafSize: 0.4 # default: 0.4 - outdoor, 0.2 - indoor
  47. mappingCornerLeafSize: 0.2 # default: 0.2 - outdoor, 0.1 - indoor
  48. mappingSurfLeafSize: 0.4 # default: 0.4 - outdoor, 0.2 - indoor
  49. # robot motion constraint (in case you are using a 2D robot)
  50. z_tollerance: 1000 # meters
  51. rotation_tollerance: 1000 # radians
  52. # CPU Params
  53. numberOfCores: 4 # number of cores for mapping optimization
  54. mappingProcessInterval: 0.15 # seconds, regulate mapping frequency
  55. # Surrounding map
  56. surroundingkeyframeAddingDistThreshold: 1.0 # meters, regulate keyframe adding threshold 选取关键帧的距离阈值
  57. surroundingkeyframeAddingAngleThreshold: 0.2 # radians, regulate keyframe adding threshold 角度阈值
  58. surroundingKeyframeDensity: 2.0 # meters, downsample surrounding keyframe poses no_used
  59. surroundingKeyframeSearchRadius: 50.0 # meters, within n meters scan-to-map optimization (when loop closure disabled) no_used
  60. # Loop closure
  61. loopClosureEnableFlag: true
  62. loopClosureFrequency: 4.0 # Hz, regulate loop closure constraint add frequency
  63. surroundingKeyframeSize: 50 # submap size (when loop closure enabled)
  64. historyKeyframeSearchRadius: 20.0 # meters, key frame that is within n meters from current pose will be considerd for loop closure
  65. historyKeyframeSearchTimeDiff: 30.0 # seconds, key frame that is n seconds older will be considered for loop closure
  66. historyKeyframeSearchNum: 25 # number of hostory key frames will be fused into a submap for loop closure
  67. historyKeyframeFitnessScore: 0.3 # icp threshold, the smaller the better alignment
  68. # GPS Settings
  69. useImuHeadingInitialization: false # if using GPS data, set to "true"
  70. useGpsElevation: false # if GPS elevation is bad, set to "false"
  71. gpsCovThreshold: 2.0 # m^2, threshold for using GPS data
  72. poseCovThreshold: 0 #25.0 # m^2, threshold for using GPS data 位姿协方差阈值 from isam2
  73. # Visualization
  74. globalMapVisualizationSearchRadius: 100.0 # meters, global map visualization radius, iktree submap 的搜索范围
  75. globalMapVisualizationPoseDensity: 10 # meters, global map visualization keyframe density
  76. globalMapVisualizationLeafSize: 1.0 # meters, global map visualization cloud density
  77. # visual iktree_map
  78. visulize_IkdtreeMap: true
  79. # visual iktree_map
  80. recontructKdTree: true
  81. # Export settings
  82. savePCD: true # https://github.com/TixiaoShan/LIO-SAM/issues/3
  83. savePCDDirectory: "/fast_lio_sam_ws/src/FAST_LIO_SAM/PCD/" # in your home folder, starts and ends with "/". Warning: the code deletes "LOAM" folder then recreates it. See "mapOptimization" for implementation