lio_sam: useRing: false useOdom: true # Topics pointCloudTopic: "rslidar_points" # Point cloud data imuTopic: "imu_data" # IMU data odomTopic: "odom" # IMU pre-preintegration odometry, same frequency as IMU gpsTopic: "odometry/gpsz" # GPS odometry topic from navsat, see module_navsat.launch file # Frames lidarFrame: "base_link" baselinkFrame: "base_link" odometryFrame: "odom" mapFrame: "map" # GPS Settings useImuHeadingInitialization: true # if using GPS data, set to "true" useGpsElevation: false # if GPS elevation is bad, set to "false" gpsCovThreshold: 2.0 # m^2, threshold for using GPS data poseCovThreshold: 25.0 # m^2, threshold for using GPS data # Export settings savePCD: true # https://github.com/TixiaoShan/LIO-SAM/issues/3 saveJson: true # https://github.com/TixiaoShan/LIO-SAM/issues/3 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 mapPath: "/work/file/map/" # 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 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.9939570888238808e-03 imuGyrNoise: 1.5636343949698187e-03 imuAccBiasN: 6.4356659353532566e-05 imuGyrBiasN: 3.5640318696367613e-05 imuGravity: 9.81 # imuGravity: 0 imuRPYWeight: 0.01 odomYaw: 0 extrinsicTrans: [ 0.0,0,0] # extrinsicTrans: [ -8.086759e-01, 3.195559e-01, -7.997231e-01 ] # extrinsicRPY: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] # extrinsicRot: [1.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0] # Extrinsics (lidar -> IMU) # extrinsicTrans: [0.0, 0.0, 0.0] # extrinsicRot: [-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] extrinsicRot: [1, 0, 0, 0, 1, 0, 0, 0, 1] extrinsicRPY: [1, 0, 0, 0, 1, 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 - outdoor, 0.2 - indoor mappingCornerLeafSize: 0.1 # 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: 0 # meters rotation_tollerance: 0 # radians # CPU Params numberOfCores: 8 # 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: 1.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 loopClosureFrequency: 2.0 # Hz, regulate loop closure constraint add frequency surroundingKeyframeSize: 50 # submap size (when loop closure enabled) historyKeyframeSearchRadius: 2.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: 1.0 # meters, global map visualization keyframe density globalMapVisualizationLeafSize: 0.2 # meters, global map visualization cloud density #Localization addKeyFameNum: 0 ndtMinScore: 1.0 # Navsat (convert GPS coordinates to Cartesian) navsat: frequency: 50 wait_for_datum: false delay: 0.0 magnetic_declination_radians: 0 yaw_offset: 0 zero_altitude: true broadcast_utm_transform: false broadcast_utm_transform_as_parent_frame: false publish_filtered_gps: false # EKF for Navsat ekf_gps: publish_tf: false map_frame: map odom_frame: odom base_link_frame: base_link world_frame: odom frequency: 50 two_d_mode: false sensor_timeout: 0.01 # ------------------------------------- # External IMU: # ------------------------------------- imu0: imu_correct # 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 imu0_config: [ false, false, false, true, true, true, false, false, false, false, false, true, true, true, true ] imu0_differential: false imu0_queue_size: 50 imu0_remove_gravitational_acceleration: true # ------------------------------------- # Odometry (From Navsat): # ------------------------------------- odom0: odometry/gps odom0_config: [ true, true, true, false, false, false, false, false, false, false, false, false, false, false, false ] odom0_differential: false odom0_queue_size: 10 # x y z r p y x_dot y_dot z_dot r_dot p_dot y_dot x_ddot y_ddot z_ddot process_noise_covariance: [ 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 10.0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.03, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.04, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.01, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0.015 ]