123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475 |
- # project name
- PROJECT_NAME: "lvi_sam"
- lvi_sam:
- # Topics
- pointCloudTopic: "/rslidar_points" # Point cloud data
- imuTopic: "/handsfree/imu" # IMU data
- # Heading
- useImuHeadingInitialization: false # if using GPS data, set to "true"
- # Export settings
- savePCD: true # https://github.com/TixiaoShan/LIO-SAM/issues/3
- saveJson: true # https://github.com/TixiaoShan/LIO-SAM/issues/3
- savePCDDirectory: "/work/map/" # in your home folder, starts and ends with "/". Warning: the code deletes "LOAM" folder then recreates it. See "mapOptimization" for implementation
- # Sensor Settings
- N_SCAN: 32 # number of lidar channel (i.e., 16, 32, 64, 128)
- Horizon_SCAN: 1800 # lidar horizontal resolution (Velodyne:1800, Ouster:512,1024,2048)
- timeField: "time" # point timestamp field, Velodyne - "time", Ouster - "t"
- downsampleRate: 1 # default: 1. Downsample your data if too many points. i.e., 16 = 64 / 4, 16 = 16 / 1
- lidarMinRange: 1.0 # default: 1.0, minimum lidar range to be used
- lidarMaxRange: 200.0 # default: 1000.0, maximum lidar range to be used
- # IMU Settings
- imuAccNoise: 3.6736505844052338e-02
- imuGyrNoise: 1.5727292142586351e-03
- imuAccBiasN: 7.0168288079436173e-04
- imuGyrBiasN: 5.9547994868495480e-06
- imuGravity: 9.80511
- # Extrinsics (lidar -> IMU)
- extrinsicTrans: [ 0.0, 0.0, 0.0 ]
- extrinsicRot: [ 1, 0, 0, 0, 1, 0, 0, 0, 1 ]
- extrinsicRPY: [ 1, 0, 0, 0, 1, 0, 0, 0, 1 ]
- # extrinsicRot: [ 0, 1, 0, -1, 0, 0, 0, 0, 1 ]
- # extrinsicRPY: [ 0, 1, 0, -1, 0, 0, 0, 0, 1 ]
- # LOAM feature threshold
- edgeThreshold: 1.0
- surfThreshold: 0.1
- edgeFeatureMinValidNum: 10
- surfFeatureMinValidNum: 100
- # voxel filter paprams
- odometrySurfLeafSize: 0.2 # default: 0.4
- mappingCornerLeafSize: 0.1 # default: 0.2
- mappingSurfLeafSize: 0.2 # default: 0.4
- # robot motion constraint (in case you are using a 2D robot)
- z_tollerance: 1000 # meters
- rotation_tollerance: 1000 # radians
- # CPU Params
- numberOfCores: 4 # number of cores for mapping optimization
- mappingProcessInterval: 0.15 # seconds, regulate mapping frequency
- # Surrounding map
- surroundingkeyframeAddingDistThreshold: 0.1 # meters, regulate keyframe adding threshold
- surroundingkeyframeAddingAngleThreshold: 0.2 # radians, regulate keyframe adding threshold
- surroundingKeyframeDensity: 2.0 # meters, downsample surrounding keyframe poses
- surroundingKeyframeSearchRadius: 50.0 # meters, within n meters scan-to-map optimization (when loop closure disabled)
- # Loop closure
- loopClosureEnableFlag: true
- surroundingKeyframeSize: 25 # submap size (when loop closure enabled)
- historyKeyframeSearchRadius: 5.0 # meters, key frame that is within n meters from current pose will be considerd for loop closure
- historyKeyframeSearchTimeDiff: 30.0 # seconds, key frame that is n seconds older will be considered for loop closure
- historyKeyframeSearchNum: 25 # number of hostory key frames will be fused into a submap for loop closure
- historyKeyframeFitnessScore: 0.3 # icp threshold, the smaller the better alignment
- # Visualization
- globalMapVisualizationSearchRadius: 1000.0 # meters, global map visualization radius
- globalMapVisualizationPoseDensity: 10.0 # meters, global map visualization keyframe density
- globalMapVisualizationLeafSize: 1.0 # meters, global map visualization cloud density
|