TixiaoShan / LIO-SAM

LIO-SAM: Tightly-coupled Lidar Inertial Odometry via Smoothing and Mapping
BSD 3-Clause "New" or "Revised" License
3.25k stars 1.22k forks source link

Run in NCLT Dataset #438

Open PigletPh opened 1 year ago

PigletPh commented 1 year ago

Hi, I tried to use LIO-SAM running on the NCLT Dataset, and my configure.yaw is followed by: lio_sam:

Topics

pointCloudTopic: "/points_raw" # Point cloud data imuTopic: "/imu_raw" # IMU data odomTopic: "odometry/imu" # 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: false # 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: false # https://github.com/TixiaoShan/LIO-SAM/issues/3 savePCDDirectory: "/home/user/Desktop/scliosam/data/" # use global path, and end with "/"

warning: if you have already data in the above savePCDDirectory, it will all remove and remake them. Thus, backup is recommended if pre-made data exist.

Sensor Settings

sensor: velodyne # lidar sensor type, either 'velodyne' or 'ouster' 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) 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: 1000.0 # default: 1000.0, maximum lidar range to be used

IMU Settings

imuAccNoise: 0.1 imuGyrNoise: 0.1 imuAccBiasN: 0.0001 imuGyrBiasN: 0.0001 imuGravity: 9.80416 imuRPYWeight: 0.01

Extrinsics (lidar -> IMU, of NCLT dataset)

extrinsicTrans: [0.112, 0.176, -0.247] extrinsicRot: [ 1, 0, 0, 0, 1, 0, 0, 0, 1] extrinsicRPY: [ 1, 0, 0, 0, 1, 0, 0, 0, 1]

When I run roslaunch lio_sam run.launch, there is no display in RVIZ. How to solve it? Thanks!

CcenShuai commented 7 months ago

have you solved this problem , i met the same problem

QiHanY commented 7 months ago

i met the same problem , i find it cause by timestamp of imu. do you have solved it ?

Spirquel commented 4 months ago

in the readMe, it said "In Rviz, uncheck "Map (cloud)" and check "Map (global)". Also check "Odom GPS", which visualizes the GPS odometry. " it's maybe for that.

JACKLiuDay commented 1 month ago
    timeScanEnd = timeScanCur + (laserCloudIn->points.back().time)/1000000;

    // check dense flag
    if (laserCloudIn->is_dense == false)
    {
        ROS_ERROR("Point cloud is not in dense format, please remove NaN points first!");
        ros::shutdown();
    }

    if (!has_ring)
    {
        return true;
    }

In imageProjection.cpp, change 264 timeScanEnd = timeScanCur + (laserCloudIn->points.back().time)/1000000 because NCLT lidar point time is microseconds.