Direct LiDAR Odometry: Fast Localization with Dense Point Clouds

Overview

Direct LiDAR Odometry: Fast Localization with Dense Point Clouds

DLO is a lightweight and computationally-efficient frontend LiDAR odometry solution with consistent and accurate localization. It features several algorithmic innovations that increase speed, accuracy, and robustness of pose estimation in perceptually-challenging environments and has been extensively tested on aerial and legged robots.

This work was part of NASA JPL Team CoSTAR's research and development efforts for the DARPA Subterranean Challenge, in which DLO was the primary state estimation component for our fleet of autonomous aerial vehicles.


drawing drawing

drawing

Instructions

DLO requires an input point cloud of type sensor_msgs::PointCloud2 with an optional IMU input of type sensor_msgs::Imu. Note that although IMU data is not required, it can be used for initial gravity alignment and will help with point cloud registration.

Dependencies

Our system has been tested extensively on both Ubuntu 18.04 Bionic with ROS Melodic and Ubuntu 20.04 Focal with ROS Noetic, although other versions may work. The following configuration with required dependencies has been verified to be compatible:

  • Ubuntu 18.04 or 20.04
  • ROS Melodic or Noetic (roscpp, std_msgs, sensor_msgs, geometry_msgs, pcl_ros)
  • C++ 14
  • CMake >= 3.16.3
  • OpenMP >= 4.5
  • Point Cloud Library >= 1.10.0
  • Eigen >= 3.3.7

Installing the binaries from Aptitude should work though:

sudo apt install libomp-dev libpcl-dev libeigen3-dev 

Compiling

Create a catkin workspace, clone the direct_lidar_odometry repository into the src folder, and compile via the catkin_tools package (or catkin_make if preferred):

mkdir ws && cd ws && mkdir src && catkin init && cd src
git clone https://github.com/kennyjchen/direct_lidar_odometry.git
catkin build

Execution

After sourcing the workspace, launch the DLO odometry and mapping ROS nodes via:

roslaunch direct_lidar_odometry dlo.launch \
  pointcloud_topic:=/robot/velodyne_points \
  imu_topic:=/robot/vn100/imu

Make sure to edit the pointcloud_topic and imu_topic input arguments with your specific topics. If IMU is not being used, set the dlo/imu ROS param to false in cfg/dlo.yaml. However, if IMU data is available, please allow DLO to calibrate and gravity align for three seconds before moving. Note that the current implementation assumes that LiDAR and IMU coordinate frames coincide, so please make sure that the sensors are physically mounted near each other.

Test Data

For your convenience, we provide example test data here (9 minutes, ~4.2GB). To run, first launch DLO (with default point cloud and IMU topics) via:

roslaunch direct_lidar_odometry dlo.launch

In a separate terminal session, play back the downloaded bag:

rosbag play dlo_test.bag

drawing

Citation

If you found this work useful, please cite our manuscript:

@article{chen2021direct,
  title={Direct LiDAR Odometry: Fast Localization with Dense Point Clouds},
  author={Chen, Kenny and Lopez, Brett T and Agha-mohammadi, Ali-akbar and Mehta, Ankur},
  journal={arXiv preprint arXiv:2110.00605},
  year={2021}
}

Acknowledgements

We thank the authors of the FastGICP and NanoFLANN open-source packages:

  • Kenji Koide, Masashi Yokozuka, Shuji Oishi, and Atsuhiko Banno, “Voxelized GICP for Fast and Accurate 3D Point Cloud Registration,” in IEEE International Conference on Robotics and Automation (ICRA), IEEE, 2021, pp. 11 054–11 059.
  • Jose Luis Blanco and Pranjal Kumar Rai, “NanoFLANN: a C++ Header-Only Fork of FLANN, A Library for Nearest Neighbor (NN) with KD-Trees,” https://github.com/jlblancoc/nanoflann, 2014.

License

This work is licensed under the terms of the MIT license.


drawing drawing

drawing drawing

Comments
  • Coordinate system conversion

    Coordinate system conversion

    Hi, thanks for your great work. I used my lidar and imu to record the data set and run it in DLO. The following figure is the map generated by the algorithm. I found that IMU drift is very serious. Is this related to coordinate system transformation? How can I set up and configure files to improve this situation? d0724d53975aa58f749b1abfa692456 3ae5711ad4dc74f03c683af98bc7db9

    opened by HomieRegina 15
  • HI, I use the nanoicp to location, but it cann`t work

    HI, I use the nanoicp to location, but it cann`t work

    Thanks for your work, I want to use nanoicp to location, it cann`t work right, but I use the pcl Gicp, it can work, so, there is anything i need to do?

    opened by tust13018211 10
  • Map generation

    Map generation

    Hi, How is the map generated? What algorithm is used? Can we upload a pcd map of the environment and then apply dlo just for localisation? I assumed dlo as a localisation algorithm, but it seems to take in the point cloud data from the bag file and generate a map on its own.

    opened by Srichitra-S 9
  • gicp speed

    gicp speed

    I run source code each scan's gicp process just cost 2-3 ms, when i run my own code use gicp library it cost 100-200ms. Both Input cloud's size almost same, which setting options may cause this phenomenon?

    opened by yst1 8
  • how to localize on a given pcd map?

    how to localize on a given pcd map?

    i have a trouble understanding how to localise on a given 3d pcd map, can anyone explain the steps

    i have a pcd map which i can load into rviz, and i have lidar-points and imu data, then how to use this package for localization?

    opened by srinivasrama 6
  • jacobian

    jacobian

    Hello author, I want to derive the jacobian in the code. I see we use global perturbation to update. When i try this, i meet this problem to look for your help. image When using Woodbury matrix identity it seems to make the formula more complicated, so i'm stuck to look for your help. Thanks for your help in advance!

    Best regards Xiaoliang jiao

    opened by narutojxl 6
  • the transformation between your lidar and imu?

    the transformation between your lidar and imu?

    I use a vlp16 lidar and a microstran imu(3DM-GX5-25) to run your program. But I failed. I think my transformation between imu and lidar is different from yours. So could you tell your true transformation between imu and lidar. the following pitcure is my configuration: 453670779 Thank you very much!

    opened by nonlinear1 6
  • Conversion of lidar and IMU coordinate system

    Conversion of lidar and IMU coordinate system

    Hi! I use a vlp16 lidar and a microstran imu(3DM-GX5-25) to record bags. And here is the part of the map I built with your algorithm. Because the coordinate systems of IMU and lidar are not consistent in the physical direction, this has affected the construction of the two-layer environment. Could you please tell me how to convert IMU and lidar coordinate system? 图片

    opened by HomieRegina 4
  • some trivial questions

    some trivial questions

    Hello authors, I have some trivial questions to look for your help. Thanks for your help.

    opened by narutojxl 4
  • Coordinate Frame

    Coordinate Frame

    Hi,

    Thank you for sharing this great work.

    I've set of problem such as defining the coordinate system of the odometry . Which coordinate frame do you use for odometry NED or BODY. I thought you use NED coordinate frame so that I expected when I move Lidar + IMU to the North direction, x should be positive increased but it has not been stable behaviour. I also moved the system to the East direction it should be caused positive increase on y axis but same problem. I think you use BODY frame or something different coordinate frame for odometry.

    I wonder also how do you send odometry information to the autopilot of drone. I prefered mavros and selected the related odometry ros topic and send them without change so I saw the odometry message in the autopilot but when odometry receive to the autopilot of drone it looks like x and y exchanged in autopilot even they are not exchanged odometry output of direct lidar odometry.

    Summary of the Question is that which coordinate frame do you use for odometry ? How can I set up the odometry frame to NED? x and y are negative decreased when I move lidar+imu to the North and the East respectively. and Z looks like 180 reversed. Should I multiply x and y with minus or apply rotation matrix to fix negative decreasing x, y odometry ?

    How can I ensure that autopilot and your odometry coordinate plane are in the same coordinate plane ?

    opened by danieldive 3
  • How to correct point cloud caused by motion?

    How to correct point cloud caused by motion?

    Hi, thank you for your great work about DLO. I have a question. When the robot is moving fast, the lidar point cloud will generate distortion due to movement, which will cause negative impact on the construction of the map. So how did DLO deal with this problem?

    opened by JACKLiuDay 2
Releases(v1.4.2)
Owner
VECTR at UCLA
Verifiable & Control-Theoretic Robotics Laboratory
VECTR at UCLA
A Robust LiDAR-Inertial Odometry for Livox LiDAR

LIO-Livox (A Robust LiDAR-Inertial Odometry for Livox LiDAR) This respository implements a robust LiDAR-inertial odometry system for Livox LiDAR. The

livox 363 Dec 26, 2022
Livox-Mapping - An all-in-one and ready-to-use LiDAR-inertial odometry system for Livox LiDAR

Livox-Mapping This repository implements an all-in-one and ready-to-use LiDAR-inertial odometry system for Livox LiDAR. The system is developed based

null 257 Dec 27, 2022
Implementation of Monocular Direct Sparse Localization in a Prior 3D Surfel Map (DSL)

Implementation of Monocular Direct Sparse Localization in a Prior 3D Surfel Map (DSL)

Haoyang Ye 93 Nov 30, 2022
This package provides localization in a pre-built map using ICP and odometry (or the IMU measurements).

Localization using ICP in a known map Overview This package localizes the lidar sensor in a given map using the ICP algorithm. It subscribes to lidar

Robotic Systems Lab - Legged Robotics at ETH Zürich 131 Jan 3, 2023
The QPEP-Enhanced Direct Sparse Odometry (DSO) with Loop Closure

QPEP-DSO: Quadratic Pose Estimation Problems (QPEP) Enhanced Direct Sparse Odometry with Loop Closure Code Arch The codes are motivated by DSO (https:

Jin Wu 8 Jun 23, 2022
This repo includes SVO Pro which is the newest version of Semi-direct Visual Odometry (SVO) developed over the past few years at the Robotics and Perception Group (RPG).

rpg_svo_pro This repo includes SVO Pro which is the newest version of Semi-direct Visual Odometry (SVO) developed over the past few years at the Robot

Robotics and Perception Group 1k Dec 26, 2022
A ROS package for mobile robot localization with 2D LiDAR

mcl_ros About mcl_ros mcl_ros is a ROS package for mobile robot localization with 2D LiDAR. To implement localization, Monte Carlo localization (MCL)

Naoki Akai 47 Oct 13, 2022
A simple localization framework that can re-localize in one point-cloud map.

Livox-Localization This repository implements a point-cloud map based localization framework. The odometry information is published with FAST-LIO. And

Siyuan Huang 94 Jan 2, 2023
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 Jan 8, 2023
Continuous Time LiDAR odometry

CT-ICP: Elastic SLAM for LiDAR sensors This repository implements the SLAM CT-ICP (see our article), a lightweight, precise and versatile pure LiDAR o

null 384 Dec 21, 2022
A ros package for robust odometry and mapping using LiDAR with aid of different sensors

W-LOAM A ros package for robust odometry and mapping using LiDAR with aid of different sensors Demo Video https://www.bilibili.com/video/BV1Fy4y1L7kZ?

Saki-Chen 51 Nov 2, 2022
A real-time, direct and tightly-coupled LiDAR-Inertial SLAM for high velocities with spinning LiDARs

LIMO-Velo [Alpha] ?? [16 February 2022] ?? The project is on alpha stage, so be sure to open Issues and Discussions and give all the feedback you can!

Andreu Huguet 150 Dec 28, 2022
This code converts a point cloud obtained by a Velodyne VLP16 3D-Lidar sensor into a depth image mono16.

pc2image This code converts a point cloud obtained by a Velodyne VLP16 3D-Lidar sensor into a depth image mono16. Requisites ROS Kinetic or Melodic Ve

Edison Velasco Sánchez 6 May 18, 2022
This repository uses a ROS node to subscribe to camera (hikvision) and lidar (livox) data. After the node merges the data, it publishes the colored point cloud and displays it in rviz.

fusion-lidar-camera-ROS 一、介绍 本仓库是一个ROS工作空间,其中ws_fusion_camera/src有一个工具包color_pc ws_fusion_camera │ README.md │ └───src │ └───package: c

hongyu wang 23 Dec 7, 2022
This project is used for lidar point cloud undistortion.

livox_cloud_undistortion This project is used for lidar point cloud undistortion. During the recording process, the lidar point cloud has naturally th

livox 74 Dec 20, 2022
Generate dense random crosswords

CrosswordGenerator crossword_gen is a program written in C allowing to generate random crosswords from a list of words. The following parameters are e

null 2 Oct 31, 2021
An FPGA accelerator for general-purpose Sparse-Matrix Dense-Matrix Multiplication (SpMM).

Sextans Sextans is an accelerator for general-purpose Sparse-Matrix Dense-Matrix Multiplication (SpMM). One exciting feature is that we only need to p

linghao.song 30 Dec 29, 2022
Anchor/Tag Configuration using Decawave DWM1000 UWB radios | Indoor Localization

Features This project implements the following features: Precise distance and location measurements using DWM1001 UWB radios. Nodes can be easily conf

Jonathan Pereira 25 Oct 27, 2022
Mobile platform for analysis of localization methods using the Intel RealSense T265 sensor

OptiBot Mobile platform for analysis of localization methods using the Intel RealSense T265 sensor About | Content | Implementation | License | Author

Kamil Goś 2 Feb 17, 2022