Skip to content

Commit

Permalink
update readme for kitti
Browse files Browse the repository at this point in the history
  • Loading branch information
TixiaoShan committed Jul 9, 2020
1 parent 39ba77e commit ba5c25e
Show file tree
Hide file tree
Showing 6 changed files with 25 additions and 11 deletions.
16 changes: 15 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -113,6 +113,9 @@ The user needs to prepare the point cloud data in the correct format for cloud d
* Ouster (OS1-128) dataset. No extrinsics need to be changed for this dataset if you are using the default settings. Please follow the Ouster notes below to configure the package to run with Ouster data. A video of the dataset can be found on [YouTube](https://youtu.be/O7fKgZQzkEo):
- [**Rooftop dataset**](https://drive.google.com/file/d/1Qy2rZdPudFhDbATPpblioBb8fRtjDGQj/view?usp=sharing)

* KITTI dataset. The extrinsics can be found in the Notes KITTI section below. To generate more bags using other KITTI raw data, you can use the python script provided in "config/doc/kitti2bag".
- [**2011_09_30_drive_0028**](https://drive.google.com/file/d/12h3ooRAZVTjoMrf3uv1_KriEXm33kHc7/view?usp=sharing)

## Run the package

1. Run the launch file:
Expand All @@ -139,7 +142,18 @@ rosbag play your-bag.bag -r 3
<img src="./config/doc/gps-demo.gif" alt="drawing" width="400"/>
</p>

- **KITTI dataset:** Testing with the KITTI dataset with LIO-SAM can be problematic. LIO-SAM needs a very good IMU source to function properly. The KITTI odometry sequence gives no IMU data. The KITTI raw synced dataset only gives IMU data at 10Hz, which is impossible to perform IMU pre-integration during a lidar scan. Though the KITTI raw unsynced dataset gives IMU data at 100Hz, the timestamps of the data is inconsistent, which causes pre-integration failure. Testing LIO-SAM with KITTI dataset is very similar to testing VINS-Mono with it. Interested users can find more discussions about this problem can be found [here](https://github.com/HKUST-Aerial-Robotics/VINS-Mono/issues/222).
- **KITTI:** Since LIO-SAM needs a high-frequency IMU for function properly, we need to use KITTI raw data for testing. One problem remains unsolved is that the intrinsics of the IMU is unknown, which has a big impact on the accuracy of LIO-SAM. Download the provided sample data and make the following changes in "params.yaml":
- extrinsicTrans: [-8.086759e-01, 3.195559e-01, -7.997231e-01]
- extrinsicRot: [9.999976e-01, 7.553071e-04, -2.035826e-03, -7.854027e-04, 9.998898e-01, -1.482298e-02, 2.024406e-03, 1.482454e-02, 9.998881e-01]
- extrinsicRPY: [9.999976e-01, 7.553071e-04, -2.035826e-03, -7.854027e-04, 9.998898e-01, -1.482298e-02, 2.024406e-03, 1.482454e-02, 9.998881e-01]
- N_SCAN: 64
- downsampleRate: 2 or 4
- loopClosureEnableFlag: true or false

<p align='center'>
<img src="./config/doc/kitti-map.png" alt="drawing" width="300"/>
<img src="./config/doc/kitti-demo.gif" alt="drawing" width="300"/>
</p>

- **Ouster lidar:** To make LIO-SAM work with Ouster lidar, some preparations needs to be done on hardware and software level.
- Hardware:
Expand Down
Binary file added config/doc/kitti-demo.gif
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added config/doc/kitti-map.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
4 changes: 2 additions & 2 deletions config/params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ lio_sam:
N_SCAN: 16 # number of lidar channel (i.e., 16, 32, 64, 128)
Horizon_SCAN: 1800 # lidar horizontal resolution (Velodyne:1800, Ouster:512,1024,2048)
timeField: "time" # point timestamp field, Velodyne - "time", Ouster - "t"
downsampleRate: 4 # default: 1. Downsample your data if too many points. i.e., 16 = 64 / 4, 16 = 16 / 1
downsampleRate: 1 # default: 1. Downsample your data if too many points. i.e., 16 = 64 / 4, 16 = 16 / 1

# IMU Settings
imuAccNoise: 3.9939570888238808e-03
Expand Down Expand Up @@ -70,7 +70,7 @@ lio_sam:
surroundingKeyframeSearchRadius: 50.0 # meters, within n meters scan-to-map optimization (when loop closure disabled)

# Loop closure
loopClosureEnableFlag: false
loopClosureEnableFlag: true
surroundingKeyframeSize: 25 # submap size (when loop closure enabled)
historyKeyframeSearchRadius: 15.0 # meters, key frame that is within n meters from current pose will be considerd for loop closure
historyKeyframeSearchTimeDiff: 30.0 # seconds, key frame that is n seconds older will be considered for loop closure
Expand Down
14 changes: 7 additions & 7 deletions launch/include/config/rviz.rviz
Original file line number Diff line number Diff line change
Expand Up @@ -163,7 +163,7 @@ Visualization Manager:
Topic: /lio_sam/mapping/odometry
Unreliable: false
Value: false
Enabled: true
Enabled: false
Name: Odometry
- Class: rviz/Group
Displays:
Expand All @@ -179,10 +179,10 @@ Visualization Manager:
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 0
Enabled: false
Enabled: true
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 0.99000001
Max Intensity: 0.959999979
Min Color: 0; 0; 0
Min Intensity: 0
Name: Velodyne
Expand All @@ -196,7 +196,7 @@ Visualization Manager:
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: false
Value: true
- Alpha: 1
Autocompute Intensity Bounds: true
Autocompute Value Bounds:
Expand All @@ -209,10 +209,10 @@ Visualization Manager:
Color: 255; 255; 255
Color Transformer: Intensity
Decay Time: 0
Enabled: true
Enabled: false
Invert Rainbow: false
Max Color: 255; 255; 255
Max Intensity: 0.99000001
Max Intensity: 0.790000021
Min Color: 0; 0; 0
Min Intensity: 0
Name: Reg Cloud
Expand All @@ -226,7 +226,7 @@ Visualization Manager:
Unreliable: false
Use Fixed Frame: true
Use rainbow: true
Value: true
Value: false
Enabled: true
Name: Point Cloud
- Class: rviz/Group
Expand Down
2 changes: 1 addition & 1 deletion src/mapOptmization.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -443,7 +443,7 @@ class mapOptimization : public ParamServer
if (loopClosureEnableFlag == false)
return;

ros::Rate rate(1);
ros::Rate rate(0.5);
while (ros::ok())
{
rate.sleep();
Expand Down

0 comments on commit ba5c25e

Please sign in to comment.