gisbi-kim / SC-LIO-SAM

LiDAR-inertial SLAM: Scan Context + LIO-SAM
619 stars 174 forks source link

problems processing KITTI dataset (and others) #9

Closed cbaus closed 3 years ago

cbaus commented 3 years ago

Issue #3 is already closed let me start a new one and go a bit more into details. You suggested using mini-kitti-publisher. However, It doesn't publish the IMU data so I went ahead with kitti2bag. I am getting multiple error messages. Could you @gisbi-kim comment if this is serious and how to fix them?

  1. This error comes even before I play the rosbag Client [/lio_sam_imageProjection] wants topic /kitti/oxts/imu to have datatype/md5sum [sensor_msgs/Imu/6a62c6daae103f4ff57a132d6f95cec2], but our version has [nav_msgs/Odometry/cd5e73d190d741a2f92e81eda573aca7]. Dropping connection. and repeats all throughout the run. I have set the topics as follows:

    pointCloudTopic: "/kitti/velo/pointcloud"               # Point cloud data
    imuTopic: "/kitti/oxts/imu"                         # IMU data
    odomTopic: "/kitti/oxts/imu"                   # IMU pre-preintegration odometry, same frequency as IMU
    gpsTopic: "/kitti/oxts/gps/fix"                   # GPS odometry topic from navsat, see module_navsat.launch file

    There is no separate odomTopic availble. Is it needed?

  2. Ring and intensity is always 0 in the kitti2bag file. Is this problematic?

  3. I added some code to treat the NaN value in the clouds that would through another error. I replaced the lines in imageProjection.cpp with

    boost::shared_ptr<pcl::PointCloud<PointXYZIRT>> filtered(new pcl::PointCloud<PointXYZIRT>);
    if (laserCloudIn->is_dense == false)
    {
          ROS_WARN("Point cloud is not in dense format, please remove NaN points first!");
          filtered->reserve(laserCloudIn->points.size());
          for (size_t i=0; i<laserCloudIn->points.size(); i++) {
            auto& point = laserCloudIn->points[i];
            if (!std::isfinite (point.x) ||
                !std::isfinite (point.y) ||
                !std::isfinite (point.z))
              continue;
            filtered->push_back(point);
          }
          laserCloudIn = filtered;
          //ros::shutdown();                                                                                                                                                                                       
        }
gisbi-kim commented 3 years ago

@cbaus sorry for the late response.

This is not a direct answer for you, but I think

  1. if you want to use this repository, IMU is reuiqred. please use the raw kitti data (e.g., 2011_10_03_drive_0027 (17.6 GB) in http://www.cvlibs.net/datasets/kitti/raw_data.php?type=residential)
  2. or if you want to use mini kitti publisher, please use the non-imu version of this repository, https://github.com/gisbi-kim/SC-A-LOAM

Thank you!

cbaus commented 3 years ago

Thanks for your kind reply. I ended up using another repository of yours for non-imu data and adjusted it to give the required output that Removert needs. It worked quite well even with the KITTI dataset. Maybe I'll go back and try with adding the IMU data at some point via SC-LIO-SAM.

Here is a summary of the steps and the code adjustment required for SC-LeGO-LOAM

Hope you like it. In any case, I like the stuff you are working on :+1:

gisbi-kim commented 3 years ago

@cbaus great! and thank you for the nice article that summarized our works :)