1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495 |
- common:
- lid_topic: "/points_raw"
- imu_topic: "/imu_correct"
- #NCLT
- # lid_topic: "/points_raw"
- # imu_topic: "/imu_raw"
- #KITTI
- # lid_topic: "/kitti/velo/pointcloud"
- # imu_topic: "/kitti/oxts/imu"
- #RS LiDar
- # lid_topic: "/rslidar"
- # imu_topic: "/imu"
- time_sync_en: false # ONLY turn on when external time synchronization is really not possible
-
- preprocess:
- lidar_type: 2 # 1 for Livox serials LiDAR, 2 for Velodyne LiDAR, 3 for ouster LiDAR,
- scan_line: 16
- scan_rate: 10 # only need to be set for velodyne, unit: Hz,
- blind: 1
- point_filter_num: 1
- mapping:
- acc_cov: 3.9939570888238808e-03
- gyr_cov: 1.5636343949698187e-03
- b_acc_cov: 6.4356659353532566e-05
- b_gyr_cov: 3.5640318696367613e-05
- fov_degree: 180
- det_range: 100.0
- extrinsic_est_en: true # true: enable the online estimation of IMU-LiDAR extrinsic,
- extrinsic_T: [ 0, 0, 0]
- extrinsic_R: [ 1, 0, 0,
- 0, 1, 0,
- 0, 0, 1]
- publish:
- path_en: true
- scan_publish_en: true # false: close all the point cloud output
- dense_publish_en: false # false: low down the points number in a global-frame point clouds scan.
- scan_bodyframe_pub_en: false # true: output the point cloud scans in IMU-body-frame
- pcd_save:
- pcd_save_en: false
- interval: -1 # how many LiDAR frames saved in each pcd file;
- # -1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames.
- # voxel filter paprams
- odometrySurfLeafSize: 0.2 # default: 0.4 - outdoor, 0.2 - indoor
- mappingCornerLeafSize: 0.2 # default: 0.2 - outdoor, 0.1 - indoor
- mappingSurfLeafSize: 0.2 # default: 0.4 - outdoor, 0.2 - indoor
- # 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 # use loopclousre or not
- loopClosureFrequency: 4.0 # Hz, regulate loop closure constraint add frequency
- surroundingKeyframeSize: 50 # submap size (when loop closure enabled)
- historyKeyframeSearchRadius: 1.5 # 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: 20 # 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 # meters, global map visualization keyframe density
- globalMapVisualizationLeafSize: 1.0 # meters, global map visualization cloud density
- # visual iktree_map
- visulize_IkdtreeMap: true
- # visual iktree_map
- recontructKdTree: true
- # Export settings
- locate_mode: true
- savePCD: true # https://github.com/TixiaoShan/LIO-SAM/issues/3
- savePCDDirectory: "/doc/ros_ws/map/large_vlp" # in your home folder, starts and ends with "/". Warning: the code deletes "LOAM" folder then recreates it. See "mapOptimization" for implementation
|