# LeGO-LOAM
This repository contains code for a lightweight and ground optimized lidar odometry and mapping (LeGO-LOAM) system for ROS compatible UGVs. The system takes in point cloud from a Velodyne VLP-16 Lidar (palced horizontally) and optional IMU data as inputs. It outputs 6D pose estimation in real-time. A demonstration of the system can be found here -> https://www.youtube.com/watch?v=O3tz_ftHV48
<!--
[![Watch the video](/LeGO-LOAM/launch/demo.gif)](https://www.youtube.com/watch?v=O3tz_ftHV48)
-->
<p align='center'>
<img src="/LeGO-LOAM/launch/demo.gif" alt="drawing" width="800"/>
</p>
## Lidar-inertial Odometry
An updated lidar-initial odometry package, [LIO-SAM](https://github.com/TixiaoShan/LIO-SAM), has been open-sourced and available for testing.
## Dependency
- [ROS](http://wiki.ros.org/ROS/Installation) (tested with indigo, kinetic, and melodic)
- [gtsam](https://github.com/borglab/gtsam/releases) (Georgia Tech Smoothing and Mapping library, 4.0.0-alpha2)
```
wget -O ~/Downloads/gtsam.zip https://github.com/borglab/gtsam/archive/4.0.0-alpha2.zip
cd ~/Downloads/ && unzip gtsam.zip -d ~/Downloads/
cd ~/Downloads/gtsam-4.0.0-alpha2/
mkdir build && cd build
cmake ..
sudo make install
```
## Compile
You can use the following commands to download and compile the package.
```
cd ~/catkin_ws/src
git clone https://github.com/RobustFieldAutonomyLab/LeGO-LOAM.git
cd ..
catkin_make -j1
```
When you compile the code for the first time, you need to add "-j1" behind "catkin_make" for generating some message types. "-j1" is not needed for future compiling.
## The system
LeGO-LOAM is speficifally optimized for a horizontally placed VLP-16 on a ground vehicle. It assumes there is always a ground plane in the scan. The UGV we are using is Clearpath Jackal. It has a built-in IMU.
<p align='center'>
<img src="/LeGO-LOAM/launch/jackal-label.jpg" alt="drawing" width="400"/>
</p>
The package performs segmentation before feature extraction.
<p align='center'>
<img src="/LeGO-LOAM/launch/seg-total.jpg" alt="drawing" width="400"/>
</p>
Lidar odometry performs two-step Levenberg Marquardt optimization to get 6D transformation.
<p align='center'>
<img src="/LeGO-LOAM/launch/odometry.jpg" alt="drawing" width="400"/>
</p>
## New Lidar
The key thing to adapt the code to a new sensor is making sure the point cloud can be properly projected to an range image and ground can be correctly detected. For example, VLP-16 has a angular resolution of 0.2° and 2° along two directions. It has 16 beams. The angle of the bottom beam is -15°. Thus, the parameters in "utility.h" are listed as below. When you implement new sensor, make sure that the ground_cloud has enough points for matching. Before you post any issues, please read this.
```
extern const int N_SCAN = 16;
extern const int Horizon_SCAN = 1800;
extern const float ang_res_x = 0.2;
extern const float ang_res_y = 2.0;
extern const float ang_bottom = 15.0;
extern const int groundScanInd = 7;
```
Another example for Velodyne HDL-32e range image projection:
```
extern const int N_SCAN = 32;
extern const int Horizon_SCAN = 1800;
extern const float ang_res_x = 360.0/Horizon_SCAN;
extern const float ang_res_y = 41.333/float(N_Scan-1);
extern const float ang_bottom = 30.666666;
extern const int groundScanInd = 20;
```
**New**: a new **useCloudRing** flag has been added to help with point cloud projection (i.e., VLP-32C, VLS-128). Velodyne point cloud has "ring" channel that directly gives the point row id in a range image. Other lidars may have a same type of channel, i.e., "r" in Ouster. If you are using a non-Velodyne lidar but it has a similar "ring" channel, you can change the PointXYZIR definition in utility.h and the corresponding code in imageProjection.cpp.
For **KITTI** users, if you want to use our algorithm with **HDL-64e**, you need to write your own implementation for such projection. If the point cloud is not projected properly, you will lose many points and performance.
If you are using your lidar with an IMU, make sure your IMU is aligned properly with the lidar. The algorithm uses IMU data to correct the point cloud distortion that is cause by sensor motion. If the IMU is not aligned properly, the usage of IMU data will deteriorate the result. Ouster lidar IMU is not supported in the package as LeGO-LOAM needs a 9-DOF IMU.
## Run the package
1. Run the launch file:
```
roslaunch lego_loam run.launch
```
Notes: The parameter "/use_sim_time" is set to "true" for simulation, "false" to real robot usage.
2. Play existing bag files:
```
rosbag play *.bag --clock --topic /velodyne_points /imu/data
```
Notes: Though /imu/data is optinal, it can improve estimation accuracy greatly if provided. Some sample bags can be downloaded from [here](https://github.com/RobustFieldAutonomyLab/jackal_dataset_20170608).
## New data-set
This dataset, [Stevens data-set](https://github.com/TixiaoShan/Stevens-VLP16-Dataset), is captured using a Velodyne VLP-16, which is mounted on an UGV - Clearpath Jackal, on Stevens Institute of Technology campus. The VLP-16 rotation rate is set to 10Hz. This data-set features over 20K scans and many loop-closures.
<p align='center'>
<img src="/LeGO-LOAM/launch/dataset-demo.gif" alt="drawing" width="600"/>
</p>
<p align='center'>
<img src="/LeGO-LOAM/launch/google-earth.png" alt="drawing" width="600"/>
</p>
## Cite *LeGO-LOAM*
Thank you for citing [our *LeGO-LOAM* paper](./Shan_Englot_IROS_2018_Preprint.pdf) if you use any of this code:
```
@inproceedings{legoloam2018,
title={LeGO-LOAM: Lightweight and Ground-Optimized Lidar Odometry and Mapping on Variable Terrain},
author={Shan, Tixiao and Englot, Brendan},
booktitle={IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)},
pages={4758-4765},
year={2018},
organization={IEEE}
}
```
## Loop Closure
The loop-closure method implemented in this package is a naive ICP-based method. It often fails when the odometry drift is too large. For more advanced loop-closure methods, there is a package called [SC-LeGO-LOAM](https://github.com/irapkaist/SC-LeGO-LOAM), which features utilizing point cloud descriptor.
## Speed Optimization
An optimized version of LeGO-LOAM can be found [here](https://github.com/facontidavide/LeGO-LOAM/tree/speed_optimization). All credits go to @facontidavide. Improvements in this directory include but not limited to:
+ To improve the quality of the code, making it more readable, consistent and easier to understand and modify.
+ To remove hard-coded values and use proper configuration files to describe the hardware.
+ To improve performance, in terms of amount of CPU used to calculate the same result.
+ To convert a multi-process application into a single-process / multi-threading one; this makes the algorithm more deterministic and slightly faster.
+ To make it easier and faster to work with rosbags: processing a rosbag should be done at maximum speed allowed by the CPU and in a deterministic way.
+ As a consequence of the previous point, creating unit and regression tests will be easier.
没有合适的资源?快使用搜索试试~ 我知道了~
温馨提示
代码目录说明 mick_bringup : 为麦克纳姆轮和四轮差速ROS底盘的ROS节点 mick_description :存放模型文件和URDF文件 mick_navigation: move—base导航配置文件
资源推荐
资源详情
资源评论
收起资源包目录
基于激光传感器实现了简易的自主导航demo-自主导航小车项目(mick).zip (253个子文件)
example_linux_serial_port.c 2KB
rawdata.cc 25KB
input.cc 9KB
convert.cc 3KB
nodelet.cc 2KB
cloud_nodelet.cc 926B
cloud_node.cc 623B
rslidarNode.cfg 433B
CloudNode.cfg 384B
setup.cfg 71B
featureAssociation.cpp 73KB
mapOptmization.cpp 69KB
chassis_4ws4wd.cpp 27KB
mick_bringup.cpp 26KB
mickx4_bringup_v2.cpp 22KB
imageProjection.cpp 21KB
transformFusion.cpp 12KB
wit_imu.cpp 11KB
chassis_4ws4wd_node.cpp 10KB
seven_lab.cpp 9KB
pointcloud_to_laserscan_nodelet.cpp 9KB
ToRange.cpp 8KB
mick_imu.cpp 8KB
rsdriver.cpp 8KB
save_rgb_imu_from_kinect2.cpp 7KB
laserscan_to_pointcloud_nodelet.cpp 6KB
teleop_keyboard.cpp 5KB
pointcloud_to_laserscan_node.cpp 2KB
laserscan_to_pointcloud_node.cpp 2KB
transfor_joy.cpp 973B
rslidar_node.cpp 791B
range_node.cpp 602B
curves.csv 344KB
ChannelNum.csv 7KB
ChannelNum.csv 7KB
curves.csv 1KB
ChannelNum.csv 1KB
ChannelNum.csv 1KB
ChannelNum.csv 1KB
curves.csv 842B
curves.csv 715B
curves.csv 715B
angle.csv 552B
angle.csv 551B
CurveRate.csv 273B
angle.csv 155B
angle.csv 142B
angle.csv 142B
limit.csv 9B
demo.gif 18.26MB
dataset-demo.gif 3.54MB
chassis_4ws4wd.h 6KB
utility.h 6KB
rawdata.h 5KB
input.h 3KB
pointcloud_to_laserscan_nodelet.h 3KB
laserscan_to_pointcloud_nodelet.h 3KB
ToRange.h 2KB
rsdriver.h 2KB
convert.h 1KB
seg-total.jpg 136KB
jackal-label.jpg 32KB
odometry.jpg 22KB
c_cpp_properties.json 3KB
launch.json 904B
hector_slam.launch 2KB
mickx4.launch 2KB
two_lidar.launch 2KB
sample_nodelet.launch 1KB
sample_laserscan_to_pointcloud_nodelet.launch 1KB
mickx4_carto_2D.launch 1KB
sample_node.launch 1KB
xiaoqiang_pro.launch 1KB
xiaoqiang_lungu.launch 1KB
cloud_nodelet.launch 1KB
mickx4_amcl.launch 1KB
rs_lidar_32_cut_angle.launch 1KB
rs_lidar_32.launch 1KB
sample_laserscan_to_pointcloud_node.launch 1KB
rs_lidar_16.launch 1KB
rs_lidar_32_loam.launch 1KB
rslidar.launch 1KB
rs_lidar_32_pcap.launch 1KB
run.launch 941B
mickx4_bringup.launch 880B
mickx4_gmapping.launch 825B
bn880.launch 819B
mickx4_bringup_v2.launch 798B
nmea_serial_driver.launch 788B
mickm4_bringup.launch 769B
display.launch 756B
gsy4ws4wd_bringup.launch 737B
amcl.launch 638B
amcl_no_rviz.launch 638B
state_publisher.launch 521B
transfor_joy.launch 425B
test_odom.launch 424B
mick_imu.launch 371B
gmapping_no_rviz.launch 363B
gmapping.launch 354B
共 253 条
- 1
- 2
- 3
资源评论
博士僧小星
- 粉丝: 2256
- 资源: 5989
下载权益
C知道特权
VIP文章
课程特权
开通VIP
上传资源 快速赚钱
- 我的内容管理 展开
- 我的资源 快来上传第一个资源
- 我的收益 登录查看自己的收益
- 我的积分 登录查看自己的积分
- 我的C币 登录后查看C币余额
- 我的收藏
- 我的下载
- 下载帮助
安全验证
文档复制为VIP权益,开通VIP直接复制
信息提交成功