velodyne64_kitti_dataset.yaml 4.3 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889
  1. common:
  2. lid_topic: /points_raw #"/velodyne_points"
  3. imu_topic: /imu_raw #"/imu/data"
  4. time_sync_en: false # ONLY turn on when external time synchronization is really not possible
  5. #NCLT
  6. # lid_topic: "/points_raw"
  7. # imu_topic: "/imu_raw"
  8. #KITTI
  9. # lid_topic: "/kitti/velo/pointcloud"
  10. # imu_topic: "/kitti/oxts/imu"
  11. #RS LiDar
  12. # lid_topic: "/rslidar"
  13. # imu_topic: "/imu"
  14. preprocess:
  15. lidar_type: 2 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR,
  16. scan_line: 64
  17. scan_rate: 10 # only need to be set for velodyne, unit: Hz,
  18. timestamp_unit: 2 # the unit of time/t field in the PointCloud2 rostopic: 0-second, 1-milisecond, 2-microsecond, 3-nanosecond.
  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: false # true: enable the online estimation of IMU-LiDAR extrinsic,
  28. extrinsic_T: [ -8.086759e-01, 3.195559e-01, -7.997231e-01]
  29. extrinsic_R: [9.999976e-01, 7.553071e-04, -2.035826e-03, -7.854027e-04, 9.998898e-01, -1.482298e-02, 2.024406e-03, 1.482454e-02, 9.998881e-01]
  30. publish:
  31. path_en: true
  32. scan_publish_en: true # false: close all the point cloud output
  33. dense_publish_en: true # false: low down the points number in a global-frame point clouds scan.
  34. scan_bodyframe_pub_en: true # true: output the point cloud scans in IMU-body-frame
  35. pcd_save:
  36. pcd_save_en: true
  37. interval: -1 # how many LiDAR frames saved in each pcd file;
  38. # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames.
  39. # voxel filter paprams
  40. odometrySurfLeafSize: 0.4 # default: 0.4 - outdoor, 0.2 - indoor
  41. mappingCornerLeafSize: 0.2 # default: 0.2 - outdoor, 0.1 - indoor
  42. mappingSurfLeafSize: 0.4 # default: 0.4 - outdoor, 0.2 - indoor
  43. # robot motion constraint (in case you are using a 2D robot)
  44. z_tollerance: 1000 # meters
  45. rotation_tollerance: 1000 # radians
  46. # CPU Params
  47. numberOfCores: 4 # number of cores for mapping optimization
  48. mappingProcessInterval: 0.15 # seconds, regulate mapping frequency
  49. # Surrounding map
  50. surroundingkeyframeAddingDistThreshold: 10 #1.0 # meters, regulate keyframe adding threshold
  51. surroundingkeyframeAddingAngleThreshold: 0.2 # radians, regulate keyframe adding threshold
  52. surroundingKeyframeDensity: 2.0 # meters, downsample surrounding keyframe poses
  53. surroundingKeyframeSearchRadius: 50.0 # meters, within n meters scan-to-map optimization (when loop closure disabled)
  54. # Loop closure
  55. loopClosureEnableFlag: false
  56. loopClosureFrequency: 1.0 # Hz, regulate loop closure constraint add frequency
  57. surroundingKeyframeSize: 50 # submap size (when loop closure enabled)
  58. historyKeyframeSearchRadius: 5 #1.5 # meters, key frame that is within n meters from current pose will be considerd for loop closure
  59. historyKeyframeSearchTimeDiff: 30.0 # seconds, key frame that is n seconds older will be considered for loop closure
  60. historyKeyframeSearchNum: 20 # number of hostory key frames will be fused into a submap for loop closure
  61. historyKeyframeFitnessScore: 0.5 # icp threshold, the smaller the better alignment
  62. # Visualization
  63. globalMapVisualizationSearchRadius: 1000.0 # meters, global map visualization radius
  64. globalMapVisualizationPoseDensity: 10 # meters, global map visualization keyframe density
  65. globalMapVisualizationLeafSize: 1.0 # meters, global map visualization cloud density
  66. # visual iktree_map
  67. visulize_IkdtreeMap: true
  68. # visual iktree_map
  69. recontructKdTree: true
  70. # Export settings
  71. savePCD: true # https://github.com/TixiaoShan/LIO-SAM/issues/3
  72. 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