1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071 |
- # project name
- PROJECT_NAME: "lvi_sam"
- lvi_sam:
- # Topics
- pointCloudTopic: "/points_raw" # Point cloud data
- imuTopic: "/imu_raw" # IMU data
- # Heading
- useImuHeadingInitialization: true # if using GPS data, set to "true"
-
- # Export settings
- savePCD: false # https://github.com/TixiaoShan/LIO-SAM/issues/3
- savePCDDirectory: "/Downloads/LOAM/" # 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: 16 # 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
- # IMU Settings
- imuAccNoise: 3.9939570888238808e-03
- imuGyrNoise: 1.5636343949698187e-03
- imuAccBiasN: 6.4356659353532566e-05
- imuGyrBiasN: 3.5640318696367613e-05
- imuGravity: 9.80511
-
- # Extrinsics (lidar -> IMU)
- extrinsicTrans: [0.0, 0.0, 0.0]
- extrinsicRot: [-1, 0, 0, 0, 1, 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.4 # default: 0.4
- mappingCornerLeafSize: 0.2 # default: 0.2
- mappingSurfLeafSize: 0.4 # 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: 1.0 # 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: 20.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
|