params.yaml 8.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183
  1. lio_sam:
  2. useRing: false
  3. useOdom: true
  4. # Topics
  5. pointCloudTopic: "rslidar_points" # Point cloud data
  6. imuTopic: "imu_data" # IMU data
  7. odomTopic: "odom" # IMU pre-preintegration odometry, same frequency as IMU
  8. gpsTopic: "odometry/gpsz" # GPS odometry topic from navsat, see module_navsat.launch file
  9. # Frames
  10. lidarFrame: "base_link"
  11. baselinkFrame: "base_link"
  12. odometryFrame: "odom"
  13. mapFrame: "map"
  14. # GPS Settings
  15. useImuHeadingInitialization: true # if using GPS data, set to "true"
  16. useGpsElevation: false # if GPS elevation is bad, set to "false"
  17. gpsCovThreshold: 2.0 # m^2, threshold for using GPS data
  18. poseCovThreshold: 25.0 # m^2, threshold for using GPS data
  19. # Export settings
  20. savePCD: true # https://github.com/TixiaoShan/LIO-SAM/issues/3
  21. saveJson: true # https://github.com/TixiaoShan/LIO-SAM/issues/3
  22. savePCDDirectory: "/work/file/map/" # in your home folder, starts and ends with "/". Warning: the code deletes "LOAM" folder then recreates it. See "mapOptimization" for implementation
  23. mapPath: "/work/file/map/"
  24. # Sensor Settings
  25. N_SCAN: 16 # number of lidar channel (i.e., 16, 32, 64, 128)
  26. Horizon_SCAN: 1800 # lidar horizontal resolution (Velodyne:1800, Ouster:512,1024,2048)
  27. timeField: "time" # point timestamp field, Velodyne - "time", Ouster - "t"
  28. downsampleRate: 1 # default: 1. Downsample your data if too many points. i.e., 16 = 64 / 4, 16 = 16 / 1
  29. lidarMinRange: 1.0 # default: 1.0, minimum lidar range to be used
  30. lidarMaxRange: 200.0 # default: 1000.0, maximum lidar range to be used
  31. # IMU Settings
  32. imuAccNoise: 3.9939570888238808e-03
  33. imuGyrNoise: 1.5636343949698187e-03
  34. imuAccBiasN: 6.4356659353532566e-05
  35. imuGyrBiasN: 3.5640318696367613e-05
  36. imuGravity: 9.81
  37. # imuGravity: 0
  38. imuRPYWeight: 0.01
  39. odomYaw: 0
  40. extrinsicTrans: [ 0.0,0,0]
  41. # extrinsicTrans: [ -8.086759e-01, 3.195559e-01, -7.997231e-01 ]
  42. # extrinsicRPY: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
  43. # extrinsicRot: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0]
  44. # Extrinsics (lidar -> IMU)
  45. # extrinsicTrans: [0.0, 0.0, 0.0]
  46. # extrinsicRot: [-1, 0, 0,
  47. # 0, 1, 0,
  48. # 0, 0, -1]
  49. # extrinsicRot: [ 0, 1, 0,
  50. # -1, 0, 0,
  51. # 0, 0, 1 ]
  52. # extrinsicRPY: [0, 1, 0,
  53. # -1, 0, 0,
  54. # 0, 0, 1]
  55. extrinsicRot: [1, 0, 0,
  56. 0, 1, 0,
  57. 0, 0, 1]
  58. extrinsicRPY: [1, 0, 0,
  59. 0, 1, 0,
  60. 0, 0, 1]
  61. # LOAM feature threshold
  62. edgeThreshold: 1.0
  63. surfThreshold: 0.1
  64. edgeFeatureMinValidNum: 10
  65. surfFeatureMinValidNum: 100
  66. # voxel filter paprams
  67. odometrySurfLeafSize: 0.2 # default: 0.4 - outdoor, 0.2 - indoor
  68. mappingCornerLeafSize: 0.1 # default: 0.2 - outdoor, 0.1 - indoor
  69. mappingSurfLeafSize: 0.2 # default: 0.4 - outdoor, 0.2 - indoor
  70. # robot motion constraint (in case you are using a 2D robot)
  71. z_tollerance: 0 # meters
  72. rotation_tollerance: 0 # radians
  73. # CPU Params
  74. numberOfCores: 8 # number of cores for mapping optimization
  75. mappingProcessInterval: 0.15 # seconds, regulate mapping frequency
  76. # Surrounding map
  77. surroundingkeyframeAddingDistThreshold: 1.0 # meters, regulate keyframe adding threshold
  78. surroundingkeyframeAddingAngleThreshold: 0.2 # radians, regulate keyframe adding threshold
  79. surroundingKeyframeDensity: 1.0 # meters, downsample surrounding keyframe poses
  80. surroundingKeyframeSearchRadius: 50.0 # meters, within n meters scan-to-map optimization (when loop closure disabled)
  81. # Loop closure
  82. loopClosureEnableFlag: true
  83. loopClosureFrequency: 2.0 # Hz, regulate loop closure constraint add frequency
  84. surroundingKeyframeSize: 50 # submap size (when loop closure enabled)
  85. historyKeyframeSearchRadius: 2.0 # meters, key frame that is within n meters from current pose will be considerd for loop closure
  86. historyKeyframeSearchTimeDiff: 30.0 # seconds, key frame that is n seconds older will be considered for loop closure
  87. historyKeyframeSearchNum: 25 # number of hostory key frames will be fused into a submap for loop closure
  88. historyKeyframeFitnessScore: 0.3 # icp threshold, the smaller the better alignment
  89. # Visualization
  90. globalMapVisualizationSearchRadius: 1000.0 # meters, global map visualization radius
  91. globalMapVisualizationPoseDensity: 1.0 # meters, global map visualization keyframe density
  92. globalMapVisualizationLeafSize: 0.2 # meters, global map visualization cloud density
  93. #Localization
  94. addKeyFameNum: 0
  95. ndtMinScore: 1.0
  96. # Navsat (convert GPS coordinates to Cartesian)
  97. navsat:
  98. frequency: 50
  99. wait_for_datum: false
  100. delay: 0.0
  101. magnetic_declination_radians: 0
  102. yaw_offset: 0
  103. zero_altitude: true
  104. broadcast_utm_transform: false
  105. broadcast_utm_transform_as_parent_frame: false
  106. publish_filtered_gps: false
  107. # EKF for Navsat
  108. ekf_gps:
  109. publish_tf: false
  110. map_frame: map
  111. odom_frame: odom
  112. base_link_frame: base_link
  113. world_frame: odom
  114. frequency: 50
  115. two_d_mode: false
  116. sensor_timeout: 0.01
  117. # -------------------------------------
  118. # External IMU:
  119. # -------------------------------------
  120. imu0: imu_correct
  121. # make sure the input is aligned with ROS REP105. "imu_correct" is manually transformed by myself. EKF can also transform the data using tf between your imu and base_link
  122. imu0_config: [ false, false, false,
  123. true, true, true,
  124. false, false, false,
  125. false, false, true,
  126. true, true, true ]
  127. imu0_differential: false
  128. imu0_queue_size: 50
  129. imu0_remove_gravitational_acceleration: true
  130. # -------------------------------------
  131. # Odometry (From Navsat):
  132. # -------------------------------------
  133. odom0: odometry/gps
  134. odom0_config: [ true, true, true,
  135. false, false, false,
  136. false, false, false,
  137. false, false, false,
  138. false, false, false ]
  139. odom0_differential: false
  140. odom0_queue_size: 10
  141. # x y z r p y x_dot y_dot z_dot r_dot p_dot y_dot x_ddot y_ddot z_ddot
  142. process_noise_covariance: [ 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
  143. 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
  144. 0, 0, 10.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
  145. 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
  146. 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
  147. 0, 0, 0, 0, 0, 0.1, 0, 0, 0, 0, 0, 0, 0, 0, 0,
  148. 0, 0, 0, 0, 0, 0, 0.25, 0, 0, 0, 0, 0, 0, 0, 0,
  149. 0, 0, 0, 0, 0, 0, 0, 0.25, 0, 0, 0, 0, 0, 0, 0,
  150. 0, 0, 0, 0, 0, 0, 0, 0, 0.04, 0, 0, 0, 0, 0, 0,
  151. 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0,
  152. 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0,
  153. 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.5, 0, 0, 0,
  154. 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0,
  155. 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0,
  156. 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.015 ]