Giter Club home page Giter Club logo

sc-lio-sam's Introduction

SC-LIO-SAM

version 2021-06-24

What is SC-LIO-SAM?

Scan Context: A fast and robust place recognition

  • Light-weight: a single header and cpp file named "Scancontext.h" and "Scancontext.cpp"
    • Our module has KDtree and we used nanoflann. nanoflann is an also single-header-program and that file is in our directory.
  • Easy to use: A user just remembers and uses only two API functions; makeAndSaveScancontextAndKeys and detectLoopClosureID.
  • Fast: A single loop detection requires under 30 ms (for 20 x 60 size, 3 candidates)

Examples

We provide example results using MulRan dataset, which provides LiDAR and 9dof IMU data. You can see the parameter file (i.e., params_mulran.yaml) modified for MulRan dataset.

  • As seen in the above video, the combination of Scan Context loop detector and LIO-SAM's odometry is robust to highly dynamic and less structured environments (e.g., a wide road on a bridge with many moving objects).

How to use?

  • We provide a tutorial that runs SC-LIO-SAM on MulRan dataset, you can reproduce the above results by following these steps.
  1. You can download the dataset at the MulRan dataset website
  2. Place the directory SC-LIO-SAM under user catkin work space
    For example,
    cd ~/catkin_ws/src
    git clone https://github.com/gisbi-kim/SC-LIO-SAM.git
    cd ..
    catkin_make
    source devel/setup.bash
    roslaunch lio_sam run.launch # or roslaunch lio_sam run_mulran.launch
    
  3. By following this guideline, you can easily publish the MulRan dataset's LiDAR and IMU topics via ROS.

Dependency

  • All dependencies are same as the original LIO-SAM

Notes

About performance

  • We used two types of loop detetions (i.e., radius search (RS)-based as already implemented in the original LIO-SAM and Scan context (SC)-based global revisit detection). See mapOptmization.cpp for details. performSCLoopClosure is good for correcting large drifts and performRSLoopClosure is good for fine-stitching.
  • To prevent the wrong map correction, we used Cauchy (but DCS can be used) kernel for loop factor. See mapOptmization.cpp for details. We found that Cauchy is emprically enough.

Minor

  • We used C++14 to use std::make_unique in Scancontext.cpp but you can use C++11 with slightly modifying only that part.
  • We used a larger value for velocity upper bound (see failureDetection in imuPreintegration.cpp) for fast motions of a MulRan dataset's car platform.
  • The some code lines are adapted for Ouster LiDAR. Thus, if you use an other LiDAR, please refer the original author's guideline and fix some lines.
  • A LiDAR scan of MulRan dataset has no ring information, thus we simply made a hardcoding like int rowIdn = (i % 64) + 1 in imageProjection.cpp to make a ring index information that LIO-SAM requires, and it works. However, if you use an other LiDAR, you need to change this line.

Applications

  • With our save utility accompanied with this repository, we can save a set of keyframe's time, estimated pose, a corresponding point cloud, and Scan Context descriptors. The estimated poses are saved as a file named optimized_poses.txt and its format is equivalent to the famous KITTI odometry dataset's pose.txt file. For example:

  • If you use the above saved files, you can feed these data to Removert and can removing dynamic objects. No GT labels or external sensor data such as RTK-GPS is required. This tutorial guides steps from running SC-LIO-SAM to save data to Removert to remove dynamic objects in a scan. Example results are:

  • For the safe and light-weight map saver, we support off-line scan merging utils for the global map construction within user's ROI (see tools/python/makeMergedMap.py, for the details, see the tutorial video)

Cite SC-LIO-SAM

@INPROCEEDINGS { gkim-2018-iros,
  author = {Kim, Giseop and Kim, Ayoung},
  title = { Scan Context: Egocentric Spatial Descriptor for Place Recognition within {3D} Point Cloud Map },
  booktitle = { Proceedings of the IEEE/RSJ International Conference on Intelligent Robots and Systems },
  year = { 2018 },
  month = { Oct. },
  address = { Madrid }
}

and

@inproceedings{liosam2020shan,
  title={LIO-SAM: Tightly-coupled Lidar Inertial Odometry via Smoothing and Mapping},
  author={Shan, Tixiao and Englot, Brendan and Meyers, Drew and Wang, Wei and Ratti, Carlo and Rus Daniela},
  booktitle={IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)},
  pages={5135-5142},
  year={2020},
  organization={IEEE}
}

Contact

Contributors

  • Minwoo Jung: made the original LIO-SAM runs on the MulRan dataset.

Acknowledgement

  • SC-LIO-SAM is based on LIO-SAM (Tixiao Shan et al., IROS 2020). We thank Tixiao Shan and the LIO-SAM authors for providing a great base framework.

Update history

  • 2021.06.23
    • yaml file is reformatted to support the compatible form with the recent original LIO-SAM repository.
    • offline ROI global map construction python util is supported.

TODO

  • About performance
    • improve better RS loop closing (ICP test sometimes fails in reverse directions)
    • support reverse-closing of SC loops with Scan Context initial yaw
    • support SC augmentation
    • lagged RS loop closing after large drifts solved
  • About funtions for convenience
    • save extended data: nodes' time, 6D pose, node's point cloud, and corresponding SC descriptors
    • make a static map and self-labeled dynamic points by combining SC-LIO-SAM and removert.
  • Minor (not related to the performance)
    • fix the visualization issue: disappearing map points after SC loop closing
    • fix safe-save for map points after closing the program

sc-lio-sam's People

Contributors

gisbi-kim avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

sc-lio-sam's Issues

Map is not as dense as with examples

Hi

I tried using some of the original LIO-SAM datasets on SC-LIO-SAM. I adjusted all the necessary parameters in the config file as well as used the run.launch file to start the mapping.

The problem is that the map is not as dense as shown in the examples. What am I missing?

Thanks in advance

problems processing KITTI dataset (and others)

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?

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

  2. 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();                                                                                                                                                                                       
     	}

gtsam.readG2o does not read the singlesession_posegraph.g2o file

Pretty much as the title states.

When trying to read the singlesession_posegraph.g2o file with gtsam.readG2o() the graph is not compeletely read. This seems be to due to the fact that the singlesession_Posegraph.g2o file does not contain any infomartion matrix data with the edges.

What might be the simpliest and most ideal way to modifiy the saving utility to include an information matrix with the edges data?

The global map disappear after a period of time

Hello Kim,i am a new learner of lidar slam.Thank you for sharing your great job.Here is my problem:
I tried SC-LIO-SAM with the kaist01 dataset of mulran.The global map starts to disappear a period time,as the picture shown below:
disappear
the red box of the picture.
I didnt encounter this problem when i tried kaist01 with the SC-LEGOLOAM.
I guess there are some parameters about the visualization time which can be modified,but i cannot find it.
Thank you!

I still lack some files after following your video tutorial.How do I use this to get data for the removert?

First of all, thank you very much for your open source algorithm, which benefits me a lot, but there are still some things I don't understand.
I followed this video tutorial:https://www.youtube.com/watch?v=UiYYrPMcIRU
But I only got five ".pcd " such as " cloudCorner.pcd" "cloudGlobal.pcd" "cloudSurf.pcd" "trajectory.pcd" "transformations.pcd" ,I can't find a txt name "optimized_poses.txt" and I don't have a document save so many ".pcd" like "000xxx.pcd"
Is there something I'm missing?

Test with 270 degree lidar

Hello, thanks for your great job.
In my project, for the reason of occlusion, the lidar has only 270 degree。 In theory the performance would obviously be a little poorer, especially for the SC based loop closure. In my test, the loop closure recall would drop from over 90% to about 30% if the loop frame direction to the previous frame is about 30 degree.
Have you or anyone else tested with different FOV lidar (full 360 degree or partial 270 degree)? How the overall mapping error differs with different FOV lidar? And do you have any suggestion for adjusting the great algorithm to only 270 degree FOV lidar?
Thanks for your attention and I am always keeping looking forward to your kind response.

mapOtimization is killed while trying to save data

Hi,

Thanks for your addition!

When I enable the save tool it seems to save poses and everything else properly, except for the cloudGlobal.pcd. I'm guessing it might because of this:

****************************************************

Saving the posegraph ...

****************************************************

Saving map to pcd files ...

[sc_lio_sam_mapOptmization-4] escalating to SIGTERM

shutting down processing monitor...

... shutting down processing monitor complete

done

It appears the saving of cloudGlobal.pcd is interrupted as I cannot open it in CCviewer and this message is reported:

[pcl::PCDReader::read] Number of points read (6881489) is different than expected (42642378)

If anything else is needed, please let me know.

imuPreintegration node problem

lio-sam

Hi, thanks for your great job! I have tested the code with my own data and dig into the code details.
The picture shown above was the topic relationship with the related nodes. As can be seen that, the output of the imuPreintegration node influenced only the imageProjection node, where the /odometry/imu_incremental is only used to in odomDeskewInfo . From the data flow, it seems that the imuPreintegration and related constraints have little influence on the final map and trajectory.

Some tests on my own dataset:

Test1: run with imuPreintegration node

Test2: run without imuPreintegration node

Test3: run with imuPreintegration node, but the odomDeskewInfo function is disabled in imageProjection.

Result:
My own dataset1: rmse of the trajectories between Test1, Test2 and Test3 is very close (about 3mm);

My own dataset2: rmse of the trajectories between Test2, Test3 is about 0.2m, Test1 always failed and print "large velocity, reset imuPreintegration";

So does the imuPreintegration node really have little influence on the final result except that it provides /odometry/imu_incremental to help deskew the pointcloud? What is the really influence of imuPreintegration?

Or does anyone else have the same question?

Thanks for your attention and I am keeping always forward to your kind response?

Error in catkin_make

Hello. I have installed gtsam and when i catkin_make this repository after installing the requirements, I get the following error. Please let me know how to solve this:

error: no matching function for call to ‘gtsam::PreintegratedImuMeasurements::PreintegratedImuMeasurements(boost::shared_ptrgtsam::PreintegrationParams&, gtsam::imuBias::ConstantBias&)’
226 | _ = new gtsam::PreintegratedImuMeasurements(p, prior_imu_bias); // setting up the IMU integration for optimization

| ^

In file included from /home/e/catkin_ws_liosam/src/SC-LIO-SAM/SC-LIO-SAM/src/imuPreintegration.cpp:8:
/usr/local/include/gtsam/navigation/ImuFactor.h:105:3: note: candidate: ‘gtsam::PreintegratedImuMeasurements::PreintegratedImuMeasurements(const PreintegrationType&, const Matrix9&)’
105 | PreintegratedImuMeasurements(const PreintegrationType& base, const Matrix9& preintMeasCov)
| ^~~~~~~~~~~~~~~~~~~~~~~~~~~~
/usr/local/include/gtsam/navigation/ImuFactor.h:105:58: note: no known conversion for argument 1 from ‘boost::shared_ptrgtsam::PreintegrationParams’ to ‘const PreintegrationType&’ {aka ‘const gtsam::TangentPreintegration&’}
105 | PreintegratedImuMeasurements(const PreintegrationType& base, const Matrix9& preintMeasCov)
| ~~~~~~~~~~~~~~~~~~~~~~~~~~^~~~
/usr/local/include/gtsam/navigation/ImuFactor.h:94:3: note: candidate: ‘gtsam::PreintegratedImuMeasurements::PreintegratedImuMeasurements(const std::shared_ptrgtsam::PreintegrationParams&, const gtsam::imuBias::ConstantBias&)’
94 | PreintegratedImuMeasurements(const std::shared_ptr& p,
| ^~~~~~~~~~~~~~~~~~~~~~~~~~~~
/usr/local/include/gtsam/navigation/ImuFactor.h:94:77: note: no known conversion for argument 1 from ‘boost::shared_ptrgtsam::PreintegrationParams’ to ‘const std::shared_ptrgtsam::PreintegrationParams&’
94 | PreintegratedImuMeasurements(const std::shared_ptr& p,
| ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~^
/usr/local/include/gtsam/navigation/ImuFactor.h:85:3: note: candidate: ‘gtsam::PreintegratedImuMeasurements::PreintegratedImuMeasurements()’
85 | PreintegratedImuMeasurements() {
| ^~~~~~~~~~~~~~~~~~~~~~~~~~~~
/usr/local/include/gtsam/navigation/ImuFactor.h:85:3: note: candidate expects 0 arguments, 2 provided
/usr/local/include/gtsam/navigation/ImuFactor.h:72:20: note: candidate: ‘gtsam::PreintegratedImuMeasurements::PreintegratedImuMeasurements(const gtsam::PreintegratedImuMeasurements&)’
72 | class GTSAM_EXPORT PreintegratedImuMeasurements: public PreintegrationType {
| ^~~~~~~~~~~~~~~~~~~~~~~~~~~~
/usr/local/include/gtsam/navigation/ImuFactor.h:72:20: note: candidate expects 1 argument, 2 provided
/home/e/catkin_ws_liosam/src/SC-LIO-SAM/SC-LIO-SAM/src/mapOptmization.cpp: In constructor ‘mapOptimization::mapOptimization()’:
/home/e/catkin_ws_liosam/src/SC-LIO-SAM/SC-LIO-SAM/src/mapOptmization.cpp:254:13: warning: variable ‘unused’ set but not used [-Wunused-but-set-variable]
254 | int unused = system((std::string("exec rm -r ") + savePCDDirectory).c_str());
| ^~~~~~
/home/e/catkin_ws_liosam/src/SC-LIO-SAM/SC-LIO-SAM/src/mapOptmization.cpp: In member function ‘void mapOptimization::performSCLoopClosure()’:
/home/e/catkin_ws_liosam/src/SC-LIO-SAM/SC-LIO-SAM/src/mapOptmization.cpp:707:15: warning: unused variable ‘yawDiffRad’ [-Wunused-variable]
707 | float yawDiffRad = detectResult.second; // not use for v1 (because pcl icp withi initial somthing wrong...)
| ^~~~~~~~~~
make[2]: *** [SC-LIO-SAM/SC-LIO-SAM/CMakeFiles/lio_sam_imuPreintegration.dir/build.make:63: SC-LIO-SAM/SC-LIO-SAM/CMakeFiles/lio_sam_imuPreintegration.dir/src/imuPreintegration.cpp.o] Error 1
make[1]: *** [CMakeFiles/Makefile2:789: SC-LIO-SAM/SC-LIO-SAM/CMakeFiles/lio_sam_imuPreintegration.dir/all] Error 2
make[1]: *** Waiting for unfinished jobs....
[ 75%] Linking CXX executable /home/e/catkin_ws_liosam/devel/lib/lio_sam/lio_sam_featureExtraction
[ 75%] Built target lio_sam_featureExtraction
[ 81%] Linking CXX executable /home/e/catkin_ws_liosam/devel/lib/lio_sam/lio_sam_imageProjection
[ 81%] Built target lio_sam_imageProjection
[ 87%] Linking CXX executable /home/e/catkin_ws_liosam/devel/lib/lio_sam/lio_sam_mapOptmization
[ 93%] Built target lio_sam_mapOptmization
make: *** [Makefile:141: all] Error 2
Invoking "make -j8 -l8" failed

rough surface looses lock

Algorithm works great over the smooth surfaces; however, the algorithm fails off-road on rock surface. How do I adjust the parameters for this short loss of tracking. I am using the same Ouster 64 OS-1 with the Lord Parker IMU (GX25) set at 500 hz.

Rough surfaces are a challenge, but it can't be more challenging than the 360 rotation of the trials.

why sc-lio-sam and mulran player support different gps message types?

Thank you for your fabulous work. I am trying to use lt-mapper to merge two maps hence using SC-LIO-SAM to generate individual maps. In the process I notice that the GPS publisher in mulran player is of navsatfix type while GPS subscriber in SC-LIO-SAM odometry type, which result in that the later can not use information published by the former.
Is this done deliberately?

Feel confused about loopFindNearKeyframesWithRespectTo() function

Hi,thank you for your nice job for the community first. However, I feel confused about the function loopFindNearKeyframesWithRespectTo you defined.
tp
In the loopFindNearKeyframesWithRespectTo function,copy_cloudKeyPoses6D->points[0] means the transfomation from the first LiDAR frame to World frame,i.e. Twl0,which is supposed to be Identity Matrix.So when you call loopFindNearKeyframesWithRespectTo(prevKeyframeCloud, loopKeyPre, historyKeyframeSearchNum, base_key);,what is the meaning of *nearKeyframes += *transformPointCloud(cornerCloudKeyFrames[keyNear], &copy_cloudKeyPoses6D->points[_wrt_key]);The cloud is not in the same frame at all, how can they "+"?

Permissions denied.

Hi everyone,
after launching the run.launch file I get this as part of my output and I do not know how to deal with it, any ideas?

rm: cannot remove '/home/user/Desktop/data/scliosam/': No such file or directory
mkdir: cannot create directory ‘/home/user/Desktop/data/scliosam/’: No such file or directory
rm: cannot remove '/home/user/Desktop/data/scliosam/SCDs/': No such file or directory
mkdir: cannot create directory ‘/home/user’: Permission denied
rm: cannot remove '/home/user/Desktop/data/scliosam/Scans/': No such file or directory
mkdir: cannot create directory ‘/home/user’: Permission denied

Error at catkin_make.

Hi, thanks for making public this package. Here is my output at catkin_make.

Linking CXX executable /home/antonis/sc_lio_sam/devel/lib/lio_sam/lio_sam_mapOptmization
/usr/bin/ld: cannot find -lBoost::timer
collect2: error: ld returned 1 exit status
SC-LIO-SAM/SC-LIO-SAM/CMakeFiles/lio_sam_imuPreintegration.dir/build.make:759: recipe for target '/home/antonis/sc_lio_sam/devel/lib/lio_sam/lio_sam_imuPreintegration' failed
make[2]: *** [/home/antonis/sc_lio_sam/devel/lib/lio_sam/lio_sam_imuPreintegration] Error 1
CMakeFiles/Makefile2:2989: recipe for target 'SC-LIO-SAM/SC-LIO-SAM/CMakeFiles/lio_sam_imuPreintegration.dir/all' failed
make[1]: *** [SC-LIO-SAM/SC-LIO-SAM/CMakeFiles/lio_sam_imuPreintegration.dir/all] Error 2
make[1]: *** Waiting for unfinished jobs....
/usr/bin/ld: cannot find -lBoost::timer
collect2: error: ld returned 1 exit status
SC-LIO-SAM/SC-LIO-SAM/CMakeFiles/lio_sam_mapOptmization.dir/build.make:785: recipe for target '/home/antonis/sc_lio_sam/devel/lib/lio_sam/lio_sam_mapOptmization' failed
make[2]: *** [/home/antonis/sc_lio_sam/devel/lib/lio_sam/lio_sam_mapOptmization] Error 1
CMakeFiles/Makefile2:2662: recipe for target 'SC-LIO-SAM/SC-LIO-SAM/CMakeFiles/lio_sam_mapOptmization.dir/all' failed
make[1]: *** [SC-LIO-SAM/SC-LIO-SAM/CMakeFiles/lio_sam_mapOptmization.dir/all] Error 2
Makefile:140: recipe for target 'all' failed
make: *** [all] Error 2

Any ideas on how to fix ? Thanks in advance.

GPS trajectory and SLAM trajectory seem to have different orientations

Hello,

I tried to add GPS topic to SC-LIO-SAM, but the GPS trajectory and SLAM trajectory seem to have different orientations.

Before I ran run_mulran.launch, the things I changed were:

  1. Change the imu topic in line 125 of params_mulran.yaml to: imu0: /imu/data_raw
  2. Remap the imu topic in line 15 of module_navsat_mulran.launch to: <remap from="imu/data" to="imu/data_raw" />
  3. Change the frame_id of the GPS topic in the MulRan dataset to: navsat_link

Here are the results of the KAIST01 sequence in the MulRan dataset:
Screenshot 2021-10-13 22:40:15
Screenshot 2021-10-13 23:03:08

Since this angle is not 90 degrees, it does not seem to be a problem caused by the ENU coordinate system (As far as the information I refer to, Xsens yaw output is defined as the angle between East (X) and the horizontal projection of the sensor roll axis ).

I also tried to modify the tf between imu_link/navsat_link and base_link in the robot.urdf.xacro file according to the suggestions in the params_mulran.yaml file, but it does not seem to affect the results.

Am I missing any steps?

Thanks,
Zezhou Sun

missing code

void performSCLoopClosure()
{
if (cloudKeyPoses3D->points.empty() == true)
return;
// find keys
auto detectResult = scManager.detectLoopClosureID(); // first: nn index, second: yaw diff
int loopKeyCur = copy_cloudKeyPoses3D->size() - 1;;
int loopKeyPre = detectResult.first;
float yawDiffRad = detectResult.second; // not use for v1 (because pcl icp withi initial somthing wrong...)
if( loopKeyPre == -1 /* No loop found */)
return;

Missing assignments to copy_cloudKeyPoses6D, copy_cloudKeyPoses2D, and copy_cloudKeyPoses3D lead to errors at runtime.

In the previous code is:

        mtx.lock();
        *copy_cloudKeyPoses3D = *cloudKeyPoses3D;
        copy_cloudKeyPoses2D->clear();            // giseop
        *copy_cloudKeyPoses2D = *cloudKeyPoses3D; // giseop
        *copy_cloudKeyPoses6D = *cloudKeyPoses6D;
        mtx.unlock();

Error on running launch file

Hello

when im running the following command

roslaunch lio_sam run.launch

i have the following error

Screenshot from 2021-07-29 13-08-47

As i notice i have this error in all LIO-SAM projects and the reasons are the imuPreinegration and mapOptimization.

I've installed sudo apt-get install libparmetis-dev so idk whats going on here.

Any help would be appreciated.

LVI-SAM+Scan Context

Is there any open source code that combines LVI-SAM and Scan Context? Because I found that the coding styles of LVI-SAM and LIO-SAM are different.

Loop closure fails on reverse direction

Setup description:

Data was collected in a heavily wooded residential park. Sensors are mounted on top of a Unitree A1 quadruped. The lidar is VLP16, and the IMU data was collected from the ZED2i stereo camera at ~400Hz. The robot walked for ~700 seconds at around 3 km/h in a big loop. The robot returns to the starting point, but in the reverse direction.

  <link name="zed2i_imu_link"> </link>
  <joint name="imu_joint" type="fixed">
    <parent link="chassis_link" />
    <child link="zed2i_imu_link" />
    <origin xyz="0 0 0" rpy="0 0 0" />
  </joint>

Relevant parameter changes:

imuAccNoise: 2.6041145078644853e-02
imuGyrNoise: 2.1821507338697734e-03
imuAccBiasN: 8.4845638189648962e-04
imuGyrBiasN: 4.2469972559493066e-05

extrinsicRot: [1, 0, 0,
                0, 1, 0,
                0, 0, 1]
extrinsicRPY: [1, 0, 0,
                0, 1, 0,
                0, 0, 1]

z_tollerance: 1               # meters
rotation_tollerance: 0.01     # robot platform is a quadruped (unitree a1), and 
                              # with sensors on top, the body leans forward while walking. 
                              # Without this line, the produced map isn't flat.

Problem Description

Video: https://www.youtube.com/watch?v=i9tzco-p2Zs

Video was recorded with data playback x5.

At around 2:10, the robot returns to the starting position from the reverse direction, and the loop does not close. I tried tweaking the "Loop closure" parameters in the config file to no avail.

Do you have any suggestion on what parameters to tweak, etc?

I saw that at the bottom of the readme, one of the todo items seems be related to this. Is there any update on that? I hope at the very least this data can be helpful in that regard.

Problems during calculation of loop constraints

float x, y, z, roll, pitch, yaw;
Eigen::Affine3f correctionLidarFrame;
correctionLidarFrame = icp.getFinalTransformation();
// transform from world origin to wrong pose
Eigen::Affine3f tWrong = pclPointToAffine3f(copy_cloudKeyPoses6D->points[loopKeyCur]);
// transform from world origin to corrected pose
Eigen::Affine3f tCorrect = correctionLidarFrame * tWrong;// pre-multiplying -> successive rotation about a fixed frame
pcl::getTranslationAndEulerAngles (tCorrect, x, y, z, roll, pitch, yaw);
gtsam::Pose3 poseFrom = Pose3(Rot3::RzRyRx(roll, pitch, yaw), Point3(x, y, z));
gtsam::Pose3 poseTo = pclPointTogtsamPose3(copy_cloudKeyPoses6D->points[loopKeyPre]);
gtsam::Vector Vector6(6);
float noiseScore = icp.getFitnessScore();
Vector6 << noiseScore, noiseScore, noiseScore, noiseScore, noiseScore, noiseScore;
noiseModel::Diagonal::shared_ptr constraintNoise = noiseModel::Diagonal::Variances(Vector6);

On line 676 in mapOptmization.cpp, the code uses
Eigen::Affine3f tCorrect = correctionLidarFrame * tWrong;
As I understand it, if the current pointcloud is used as the source and the loop pointcloud is used as the target in ICP, then the resulting pose transformation should be $T_{correct}^{wrong}$, which should be in the form of right multiplication.
tWrong is $T_{wrong}^{world}$ ,
tCorrect is $T_{correct}^{world}$ .
we can launch:
$T_{correct}^{world} = T_{wrong}^{world} \cdot T_{correct}^{wrong}$
Eigen::Affine3f tCorrect = tWrong * correctionLidarFrame;

Sorry for taking up your time, could you help me with my doubts?

question about the scan content feature

Is Scan Content descriptor only applicable to horizontally installed multi-ring lidars? If the lidar is installed obliquely, can this descriptor still be used?

Can not run launch file

while I use roslaunch command, there is issue happened below, not sure how to fix it or I still need to change anything with the code? thanks.
[ INFO] [1644777971.817199403]: ----> Image Projection Started.
[ INFO] [1644777971.881794125]: ----> Feature Extraction Started.
[ INFO] [1644777971.894103477]: ----> IMU Preintegration Started.
rm: cannot remove '/home/user/Desktop/scliosam/data/': No such file or directory
mkdir: cannot create directory ‘/home/user/Desktop/scliosam/data/’: No such file or directory
rm: cannot remove '/home/user/Desktop/scliosam/data/SCDs/': No such file or directory
mkdir: cannot create directory ‘/home/user’: Permission denied
rm: cannot remove '/home/user/Desktop/scliosam/data/Scans/': No such file or directory
mkdir: cannot create directory ‘/home/user’: Permission denied
[ INFO] [1644777971.908546703]: ----> Map Optimization Started.

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.