T-LOAM: Truncated Least Squares Lidar-only Odometry and Mapping in Real-Time

Overview

T-LOAM: Truncated Least Squares Lidar-only Odometry and Mapping in Real-Time

The first Lidar-only odometry framework with high performance based on truncated least squares and Open3D point cloud library, The foremost improvement include:

  • Fast and precision pretreatment module, multi-region ground extraction and dynamic curved-voxel clustering perform ground point extraction and category segmentation.
  • Feature extraction based on principal component analysis(PCA) elaborate four distinctive feature,including: planar features, ground features, edge features, sphere features
  • There are three kinds of residual functions based on truncated least squares method for directly processing above features which are point-to-point, point-to-line, and point-to-plane.
  • Open3d point cloud library is integrated into SLAM algorithm framework for the first time. We extend more functions and implemented the message interface related to ROS.

[Demo Video] [Preprint Paper]

drawing

drawing drawing drawing drawing

Note that regard to pure odometry without corrections through loop closures, T-LOAM delivers much less drift than F-LOAM.

Framework overview

drawing

Each frame of the 3D LiDAR is processed as input. Four main processing modules are introduced to construct the backbone of the algorithm: (a) multi-region ground extraction module, (b) dynamic curved-voxel clustering module, (c) feature extraction module, (d) pose optimization module.

Evaluation

KITTI Sequence 00 F-LOAM T-LOAM
Translational Error(%) 1.11 0.98
Relative Error(°/100m) 0.40 0.60

Graphic Result(Path and Translation)

F-LOAM

drawing

T-LOAM

drawing

F-LOAM

drawing

T-LOAM

drawing

Dependency

-ROS(Melodic Ubuntu18.04)

sudo apt-get install python-catkin-tools ros-melodic-ecl-threads ros-melodic-jsk-recognition-msgs ros-melodic-jsk-visualization ros-melodic-velodyne-msgs

-YAML(0.6.3) Note that you must build a shared library due to we utilize the ros nodelet package.

tar -zxvf yaml-cpp-yaml-cpp-0.6.3.tar.gz
cd yaml-2.3.0 && mkdir build && cd build
cmake [-G generator] [-DYAML_BUILD_SHARED_LIBS=ON] ..
make 
sudo make install

-Open3D(A Modern Library for 3D Data Processing 0.12.0)

Please note that open3d installation will be a slightly troublesome process, please be patient. Another problem that needs attention is that Open3D-ML cannot be used in ROS at the same time due to the link error2286 and error3432. In order to fix this, you need to specify the cmake flag -DGLIBCXX_USE_CXX11_ABI=ON. However, the latest Tensorflow2.4 installed through conda(not pip) already supports the C++11 API, you can check the API with print(tensorflow.__cxx11_abi_flag__). If the flag is true, you can set the compile flag -DBUILD_TENSORFLOW_OPS=ON Next, you can complete the installation according to the instructions

cd Open3D
util/scripts/install-deps-ubuntu.sh
mkdir build && cd build 
cmake \
    -DBUILD_SHARED_LIBS=ON \
    -DPYTHON_EXECUTABLE=$(which python3) \
    -DBUILD_CUDA_MODULE=ON \
    -DGLIBCXX_USE_CXX11_ABI=ON \
    -DBUILD_LIBREALSENSE=ON  \
    -DCMAKE_BUILD_TYPE=Release \
    -DCMAKE_INSTALL_PREFIX=/usr/local \
    -DBUILD_PYTORCH_OPS=OFF \
    -DBUILD_TENSORFLOW_OPS=OFF \
    -DBUNDLE_OPEN3D_ML=ON \
    -DOPEN3D_ML_ROOT=${replace with own Open3D-ML path} \
    ../
make -j4
sudo make install 

If you have clone problems, you can download it directly from the link below.

Baidu Disk code: khy9 or Google Drive

-Ceres Solver(A large scale non-linear optimization library 2.0) you can complete the installation according to the guide

Installation

Now create the Catkin Environment:

mkdir -p ~/tloam_ws/src
cd ~/tloam_ws
catkin init
catkin config --merge-devel
catkin config --cmake-args -DCMAKE_BUILD_TYPE=Release

And clone the project:

cd src
git clone https://github.com/zpw6106/tloam.git
catkin build

Usage

Download the KITTI Odometry Dataset (Graviti can provide faster download speed in China), then organize it according to the following structure, and modify the read path in the config/kitti/kitti_reader.yaml

drawing

-Example for running T-LOAM using the KITTI Dataset

roslaunch tloam tloam_kitti.launch

Contributors

Pengwei Zhou (Email: [email protected])

BibTex Citation

Thank you for citing our T-LOAM paper on IEEEif you use any of this code:

@ARTICLE{9446309,
  author={Zhou, Pengwei and Guo, Xuexun and Pei, Xiaofei and Chen, Ci},
  journal={IEEE Transactions on Geoscience and Remote Sensing}, 
  title={T-LOAM: Truncated Least Squares LiDAR-Only Odometry and Mapping in Real Time}, 
  year={2021},
  volume={},
  number={},
  pages={1-13},
  doi={10.1109/TGRS.2021.3083606}
  }

Credits

We hereby recommend reading A-LOAM ,floam and TEASER for reference and thank them for making their work public.

License

The source code is released under GPLv3 license.

I am constantly working on improving this code. For any technical issues or commercial use, please contact me([email protected]).

You might also like...
Rasterize with the least efforts for researchers.

utils3d Rasterize and do image-based 3D transforms with the least efforts for researchers. Based on numpy and OpenGL. It could be helpful when you wan

A lane detection integrated Real-time Instance Segmentation based on YOLACT (You Only Look At CoefficienTs)
A lane detection integrated Real-time Instance Segmentation based on YOLACT (You Only Look At CoefficienTs)

Real-time Instance Segmentation and Lane Detection This is a lane detection integrated Real-time Instance Segmentation based on YOLACT (You Only Look

 Fog Simulation on Real LiDAR Point Clouds for 3D Object Detection in Adverse Weather
Fog Simulation on Real LiDAR Point Clouds for 3D Object Detection in Adverse Weather

LiDAR fog simulation Created by Martin Hahner at the Computer Vision Lab of ETH Zurich. This is the official code release of the paper Fog Simulation

VID-Fusion: Robust Visual-Inertial-Dynamics Odometry for Accurate External Force Estimation
VID-Fusion: Robust Visual-Inertial-Dynamics Odometry for Accurate External Force Estimation

VID-Fusion VID-Fusion: Robust Visual-Inertial-Dynamics Odometry for Accurate External Force Estimation Authors: Ziming Ding , Tiankai Yang, Kunyi Zhan

The Surprising Effectiveness of Visual Odometry Techniques for Embodied PointGoal Navigation
The Surprising Effectiveness of Visual Odometry Techniques for Embodied PointGoal Navigation

PointNav-VO The Surprising Effectiveness of Visual Odometry Techniques for Embodied PointGoal Navigation Project Page | Paper Table of Contents Setup

TCNN Temporal convolutional neural network for real-time speech enhancement in the time domain
TCNN Temporal convolutional neural network for real-time speech enhancement in the time domain

TCNN Pandey A, Wang D L. TCNN: Temporal convolutional neural network for real-time speech enhancement in the time domain[C]//ICASSP 2019-2019 IEEE Int

Multi-robot collaborative exploration and mapping through Voronoi partition and DRL in unknown environment
Multi-robot collaborative exploration and mapping through Voronoi partition and DRL in unknown environment

Voronoi Multi_Robot Collaborate Exploration Introduction In the unknown environment, the cooperative exploration of multiple robots is completed by Vo

Dataset Cartography: Mapping and Diagnosing Datasets with Training Dynamics
Dataset Cartography: Mapping and Diagnosing Datasets with Training Dynamics

Dataset Cartography Code for the paper Dataset Cartography: Mapping and Diagnosing Datasets with Training Dynamics at EMNLP 2020. This repository cont

Comments
  • Dynamic filter about DCVC

    Dynamic filter about DCVC

    Hi,zpw, Thanks for sharing the great jobs. I have a question about the code and the paper? I can't find the dynamic filter partion in the code ,as you said "filter out the tiny groups and potential dynamic objects" in the |||-C of the paper. Maybe I missed something, can you give me some advice?

    Thanks again!

    opened by chengwei0427 0
  • open3d

    open3d

    Hi, thanks for sharing your work! I have installed the open3d success. But, when I compile the code, I encounter the following problem. Can you give me some advices, thank you!

    error: ‘open3d::geometry::OrientedBoundingBox open3d::geometry::PointCloud2::GetOrientedBoundingBox() const’ marked ‘override’, but does not override 64 | OrientedBoundingBox GetOrientedBoundingBox() const override; | ^~~~~~~~~~~~~~~~~~~~~~ In file included from ~/tloam_ws/src/tloam/include/tloam/subscriber/cloud_subscriber.hpp:21, from ~/tloam_ws/src/tloam/src/subscriber/cloud_subscriber.cpp:10: ~/tloam_ws/src/tloam/include/tloam/models/utils/sensor_data.hpp: In member function ‘void tloam::CloudData::reset()’: ~/tloam_ws/src/tloam/include/tloam/models/utils/sensor_data.hpp:24:43: error: invalid new-expression of abstract class type ‘open3d::geometry::PointCloud2’ 24 | cloud_ptr.reset(new open3d::geometry::PointCloud2);

    opened by kinggreat24 0
  • Evaluation parameters

    Evaluation parameters

    Hi, dear author,it's a great job What evaluation tools are used to obtain the parameters(relative translational error in%/relative error in degrees per 100m) in the paper. I hope you can teach me. Thank you very much.

    opened by lgm051 0
  • Open3d with cuda9.0

    Open3d with cuda9.0

    hi,the work is excellent.But when I set up the open3d 0.12.0 environment, I used cuda9.0 and kept reporting errors. The content is as follows. Does the 0.12.0 version support cuda9.0? CMake Error at /home/zhangcz/third_parts/cmake-3.18.0-Linux-x86_64/share/cmake-3.18/Modules/CMakeDetermineCUDACompiler.cmake:552 (message): The CMAKE_CUDA_ARCHITECTURES: 75-real do not all work with this compiler. Try: 30 instead.

    opened by PigletPh 10
Owner
Pengwei Zhou
Lidar SLAM & Sensor Fusion
Pengwei Zhou
LVI-SAM: Tightly-coupled Lidar-Visual-Inertial Odometry via Smoothing and Mapping

LVI-SAM This repository contains code for a lidar-visual-inertial odometry and mapping system, which combines the advantages of LIO-SAM and Vins-Mono

Tixiao Shan 1.1k Dec 27, 2022
Deep Implicit Moving Least-Squares Functions for 3D Reconstruction

DeepMLS: Deep Implicit Moving Least-Squares Functions for 3D Reconstruction This repository contains the implementation of the paper: Deep Implicit Mo

null 103 Dec 22, 2022
DeepLM: Large-scale Nonlinear Least Squares on Deep Learning Frameworks using Stochastic Domain Decomposition (CVPR 2021)

DeepLM DeepLM: Large-scale Nonlinear Least Squares on Deep Learning Frameworks using Stochastic Domain Decomposition (CVPR 2021) Run Please install th

Jingwei Huang 130 Dec 2, 2022
High-performance moving least squares material point method (MLS-MPM) solver.

High-Performance MLS-MPM Solver with Cutting and Coupling (CPIC) (MIT License) A Moving Least Squares Material Point Method with Displacement Disconti

Yuanming Hu 2.2k Dec 31, 2022
Official PyTorch implementation of the paper "Deep Constrained Least Squares for Blind Image Super-Resolution", CVPR 2022.

Deep Constrained Least Squares for Blind Image Super-Resolution [Paper] This is the official implementation of 'Deep Constrained Least Squares for Bli

MEGVII Research 141 Dec 30, 2022
SSL_SLAM2: Lightweight 3-D Localization and Mapping for Solid-State LiDAR (mapping and localization separated) ICRA 2021

SSL_SLAM2 Lightweight 3-D Localization and Mapping for Solid-State LiDAR (Intel Realsense L515 as an example) This repo is an extension work of SSL_SL

Wang Han 王晗 1.3k Jan 8, 2023
Self-supervised Deep LiDAR Odometry for Robotic Applications

DeLORA: Self-supervised Deep LiDAR Odometry for Robotic Applications Overview Paper: link Video: link ICRA Presentation: link This is the correspondin

Robotic Systems Lab - Legged Robotics at ETH Zürich 181 Dec 29, 2022
Real-Time-Student-Attendence-System - Real Time Student Attendence System

Real-Time-Student-Attendence-System The Student Attendance Management System Pro

Rounak Das 1 Feb 15, 2022
A real-time motion capture system that estimates poses and global translations using only 6 inertial measurement units

TransPose Code for our SIGGRAPH 2021 paper "TransPose: Real-time 3D Human Translation and Pose Estimation with Six Inertial Sensors". This repository

Xinyu Yi 261 Dec 31, 2022
A customisable game where you have to quickly click on black tiles in order of appearance while avoiding clicking on white squares.

W.I.P-Aim-Memory-Game A customisable game where you have to quickly click on black tiles in order of appearance while avoiding clicking on white squar

dE_soot 1 Dec 8, 2021